sbpl_lattice_planner final heading error constant +45-deg.
I've noticed a peculiar behavior in sbpl_lattice_planner, where ~50% of actionlib requests (/map frame) result in a final heading that is consistently offset by +45-degrees. The other 50% of the time, the correct heading is obtained. In all cases, the correct (x,y) position is achieved. Thoughts?
I have verified that the correct heading is being sent (rviz markers and using /move_base_simple/goal), but the issue persists.
The pertinent launch files / parameters are below.
SBPLLatticePlanner: environment_type: XYThetaLattice planner_type: ARAPlanner allocated_time: 5.0 initial_epsilon: 3.0 forward_search: false lethal_obstacle: 5 nominalvel_mpersecs: 0.1 timetoturn45degsinplace_secs: 1.5
TrajectoryPlannerROS: #Independent settings for the local costmap transform_tolerance: 0.3 sim_time: 1.7 sim_granularity: 0.025 dwa: true vx_samples: 20 vtheta_samples: 20 max_vel_x: 0.250 #max_vel_x: 0.65 min_vel_x: 0.1 max_rotational_vel: 1.0 min_in_place_rotational_vel: 0.4 xy_goal_tolerance: 0.10 yaw_goal_tolerance: 0.06 goal_distance_bias: 0.2 path_distance_bias: .9 occdist_scale: 0.05 heading_lookahead: 0.325 oscillation_reset_dist: 0.05 holonomic_robot: true acc_lim_th: 3.2 acc_lim_x: 2.5 acc_lim_y: 2.5 heading_scoring: false heading_scoring_timestep: 0.8 holonomic_robot: true simple_attractor: false
launch node pkg="pr2_move_base" name="pr2_move_base_node" type="pr2_move_base.py" machine="c2" node ns="move_base_node/local_costmap" name="voxel_grid_throttle" pkg="topic_tools" type="throttle" args="messages voxel_grid 3.0 voxel_grid_throttled" node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen" remap from="odom" to="base_odometry/odom" remap from="cmd_vel" to="navigation/cmd_vel" param name="footprint_padding" value="0.10" param name="controller_frequency" value="10.0" param name="controller_patience" value="100.0" param name="base_global_planner" value="SBPLLatticePlanner" param name="SBPLLatticePlanner/primitive_filename" value="$(find sbpl)/matlab/mprim/pr2.mprim" /node launch