I am trying to navigate my differential drive robot to a goal with Nav2, but when it's basically reached it and it's time for orientation alignment, it stops and I start getting a bunch of these:
[ERROR] [DWBLocalPlanner]: 1.00: RotateToGoal/Nonrotation command near goal. [WARN] [controller_server]: No valid trajectories out of 420! After letting it try again many times, it keeps doing this and never manages to exit this loop.
This is my Nav2 params file at the moment:
amcl: ros__parameters: use_sim_time: False alpha1: 0.5 alpha2: 0.2 alpha3: 0.3 alpha4: 0.5 alpha5: 0.2 base_frame_id: "base_footprint" beam_skip_distance: 0.5 beam_skip_error_threshold: 0.8 beam_skip_threshold: 0.3 do_beamskip: true global_frame_id: "map" lambda_short: 0.1 laser_likelihood_max_dist: 2.0 laser_max_range: -1.0 laser_min_range: -1.0 laser_model_type: "likelihood_field" max_beams: 60 max_particles: 2000 min_particles: 500 odom_frame_id: "odom" pf_err: 0.05 pf_z: 0.99 recovery_alpha_fast: 0.2 recovery_alpha_slow: 0.002 resample_interval: 1 robot_model_type: "nav2_amcl::DifferentialMotionModel" save_pose_rate: 0.5 sigma_hit: 0.2 tf_broadcast: true transform_tolerance: 1.0 update_min_a: 0.05 update_min_d: 0.05 z_hit: 0.7 z_max: 0.05 z_rand: 0.4 z_short: 0.05 set_initial_pose: true initial_pose: x: 0.616 y: -2.717 z: 0.0 # Typically 0.0 for a 2D plane yaw: 0.0 # Replace with your desired initial orientation in radians scan_topic: scan bt_navigator: ros__parameters: use_sim_time: False global_frame: map robot_base_frame: base_link odom_topic: /odom bt_loop_duration: 100 default_server_timeout: 20 wait_for_service_timeout: 5000 # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. default_nav_to_pose_bt_xml: /home/flamethrower/robot_ws/src/robot/navigate_to_pose_w_replanning_and_recovery.xml default_nav_through_poses_bt_xml: /home/flamethrower/robot_ws/src/robot/navigate_through_poses_w_replanning_and_recovery.xml plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_compute_path_through_poses_action_bt_node - nav2_smooth_path_action_bt_node - nav2_follow_path_action_bt_node - nav2_spin_action_bt_node - nav2_wait_action_bt_node - nav2_assisted_teleop_action_bt_node - nav2_back_up_action_bt_node - nav2_drive_on_heading_bt_node - nav2_clear_costmap_service_bt_node - nav2_is_stuck_condition_bt_node - nav2_goal_reached_condition_bt_node - nav2_goal_updated_condition_bt_node - nav2_globally_updated_goal_condition_bt_node - nav2_is_path_valid_condition_bt_node - nav2_initial_pose_received_condition_bt_node - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node - nav2_distance_controller_bt_node - nav2_speed_controller_bt_node - nav2_truncate_path_action_bt_node - nav2_truncate_path_local_action_bt_node - nav2_goal_updater_node_bt_node - nav2_recovery_node_bt_node - nav2_pipeline_sequence_bt_node - nav2_round_robin_node_bt_node - nav2_transform_available_condition_bt_node - nav2_time_expired_condition_bt_node - nav2_path_expiring_timer_condition - nav2_distance_traveled_condition_bt_node - nav2_single_trigger_bt_node - nav2_goal_updated_controller_bt_node - nav2_is_battery_low_condition_bt_node - nav2_navigate_through_poses_action_bt_node - nav2_navigate_to_pose_action_bt_node - nav2_remove_passed_goals_action_bt_node - nav2_planner_selector_bt_node - nav2_controller_selector_bt_node - nav2_goal_checker_selector_bt_node - nav2_controller_cancel_bt_node - nav2_path_longer_on_approach_bt_node - nav2_wait_cancel_bt_node - nav2_spin_cancel_bt_node - nav2_back_up_cancel_bt_node - nav2_assisted_teleop_cancel_bt_node - nav2_drive_on_heading_cancel_bt_node - nav2_is_battery_charging_condition_bt_node bt_navigator_navigate_through_poses_rclcpp_node: ros__parameters: use_sim_time: False bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: False controller_server: ros__parameters: use_sim_time: False controller_frequency: 10.0 min_x_velocity_threshold: 0.1 min_y_velocity_threshold: 0.5 min_theta_velocity_threshold: 0.3 failure_tolerance: 1.0 progress_checker_plugin: "progress_checker" goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" controller_plugins: ["FollowPath"] # Progress checker parameters progress_checker: plugin: "nav2_controller::SimpleProgressChecker" required_movement_radius: 0.2 movement_time_allowance: 10.0 # Goal checker parameters #precise_goal_checker: # plugin: "nav2_controller::SimpleGoalChecker" # xy_goal_tolerance: 0.25 # yaw_goal_tolerance: 0.25 # stateful: True general_goal_checker: stateful: True plugin: "nav2_controller::SimpleGoalChecker" xy_goal_tolerance: 0.2 yaw_goal_tolerance: 0.2 # DWB parameters FollowPath: plugin: "dwb_core::DWBLocalPlanner" debug_trajectory_details: True min_vel_x: 0.1 min_vel_y: 0.0 max_vel_x: 0.3 max_vel_y: 0.0 max_vel_theta: 1.0 min_speed_xy: 0.1 max_speed_xy: 0.3 min_speed_theta: 0.3 # Add high threshold velocity for turtlebot 3 issue. # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 acc_lim_x: 2.5 acc_lim_y: 0.0 acc_lim_theta: 3.2 decel_lim_x: -2.5 decel_lim_y: 0.0 decel_lim_theta: -3.2 vx_samples: 20 vy_samples: 0 vtheta_samples: 20 sim_time: 1.5 linear_granularity: 0.05 angular_granularity: 0.025 transform_tolerance: 0.2 xy_goal_tolerance: 0.2 trans_stopped_velocity: 0.25 short_circuit_trajectory_evaluation: True stateful: True critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"] BaseObstacle.scale: 0.1 PathAlign.scale: 32.0 PathAlign.forward_point_distance: 0.1 GoalAlign.scale: 24.0 GoalAlign.forward_point_distance: 0.1 PathDist.scale: 32.0 GoalDist.scale: 24.0 RotateToGoal.scale: 32.0 RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 local_costmap: local_costmap: ros__parameters: update_frequency: 5.0 publish_frequency: 0.2 global_frame: odom robot_base_frame: base_link use_sim_time: False rolling_window: true width: 3 height: 3 resolution: 0.02 #robot_radius: 0.2 footprint: "[[0.2, 0.2], [0.2, -0.2], [-0.2, -0.2], [-0.2, 0.2]]" plugins: ["obstacle_layer", "inflation_layer"] filters: ["keepout_filter"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 3.0 inflation_radius: 0.3 obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True observation_sources: scan scan: topic: /scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" raytrace_max_range: 3.0 raytrace_min_range: 0.0 obstacle_max_range: 2.5 obstacle_min_range: 0.0 static_layer: plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True keepout_filter: plugin: "nav2_costmap_2d::KeepoutFilter" enabled: True filter_info_topic: "/costmap_filter_info" always_send_full_costmap: True global_costmap: global_costmap: ros__parameters: update_frequency: 1.0 publish_frequency: 0.2 global_frame: map robot_base_frame: base_link use_sim_time: False #robot_radius: 0.2 footprint: "[[0.2, 0.2], [0.2, -0.2], [-0.2, -0.2], [-0.2, 0.2]]" resolution: 0.05 track_unknown_space: true plugins: ["static_layer", "obstacle_layer", "inflation_layer"] filters: ["keepout_filter"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True observation_sources: scan scan: topic: /scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" raytrace_max_range: 3.0 raytrace_min_range: 0.0 obstacle_max_range: 2.5 obstacle_min_range: 0.0 static_layer: plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 3.0 inflation_radius: 0.3 keepout_filter: plugin: "nav2_costmap_2d::KeepoutFilter" enabled: True filter_info_topic: "/costmap_filter_info" always_send_full_costmap: True costmap_filter_info_server: ros__parameters: use_sim_time: false type: 0 filter_info_topic: "/costmap_filter_info" mask_topic: "/keepout_filter_mask" base: 0.0 multiplier: 1.0 filter_mask_server: ros__parameters: use_sim_time: false frame_id: "map" topic_name: "/keepout_filter_mask" yaml_filename: "/home/flamethrower/robot_ws/src/robot/worlds/map_keepout.yaml" map_server: ros__parameters: use_sim_time: False # Overridden in launch by the "map" launch configuration or provided default value. # To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below. yaml_filename: "/home/flamethrower/robot_ws/src/robot/worlds/map_save.yaml" map_saver: ros__parameters: use_sim_time: False save_map_timeout: 5.0 free_thresh_default: 0.25 occupied_thresh_default: 0.65 map_subscribe_transient_local: True planner_server: ros__parameters: expected_planner_frequency: 20.0 use_sim_time: False planner_plugins: ["GridBased"] GridBased: plugin: "nav2_navfn_planner/NavfnPlanner" tolerance: 0.2 use_astar: false allow_unknown: true smoother_server: ros__parameters: use_sim_time: False smoother_plugins: ["simple_smoother"] simple_smoother: plugin: "nav2_smoother::SimpleSmoother" tolerance: 1.0e-10 max_its: 100 do_refinement: True #smoother_server: # ros__parameters: # use_sim_time: False # smoother_plugins: ["SmoothPath"] # SmoothPath: # plugin: "nav2_constrained_smoother/ConstrainedSmoother" # minimum_turning_radius: 0.0 behavior_server: ros__parameters: costmap_topic: local_costmap/costmap_raw footprint_topic: local_costmap/published_footprint cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] spin: plugin: "nav2_behaviors/Spin" backup: plugin: "nav2_behaviors/BackUp" drive_on_heading: plugin: "nav2_behaviors/DriveOnHeading" speed: 0.1 wait: plugin: "nav2_behaviors/Wait" assisted_teleop: plugin: "nav2_behaviors/AssistedTeleop" global_frame: odom robot_base_frame: base_link transform_tolerance: 0.1 use_sim_time: false simulate_ahead_time: 2.0 max_rotational_vel: 1.0 min_rotational_vel: 0.3 rotational_acc_lim: 3.2 robot_state_publisher: ros__parameters: use_sim_time: False waypoint_follower: ros__parameters: use_sim_time: False loop_rate: 20 stop_on_failure: false waypoint_task_executor_plugin: "wait_at_waypoint" wait_at_waypoint: plugin: "nav2_waypoint_follower::WaitAtWaypoint" enabled: True waypoint_pause_duration: 200 velocity_smoother: ros__parameters: use_sim_time: False smoothing_frequency: 20.0 scale_velocities: False feedback: "OPEN_LOOP" max_velocity: [0.3, 0.0, 1.0] min_velocity: [-0.3, 0.0, -1.0] max_accel: [2.5, 0.0, 3.2] max_decel: [-2.5, 0.0, -3.2] odom_topic: "odom" odom_duration: 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0 I have tried setting the RotateToGoal critic's scale to 1000 and lookahead_time to 0.1 as suggested here: https://answers.ros.org/question/354523/ but that didn't solve it. I also tried decreasing the slowing_factor a bit, but it didn't work either. I also changed the position of the goal in case it was some inflation overlap, but that didn't seem to affect it. I'm really not sure what the problem is.
max_vel_yis zero, as areacc_lim_y,decel_lim_y, andvy_samples. The use of x and y here is not immediately clear to me, but I would expect a differential-drive robot to have two control signals: linear speed and rotational speed. In that case, I would kind of expect the y-axis to be rotation, and then if that's the case it looks like your settings are preventing any motion on the y- (rotation-) axis. Can you please comment on what the y-values are used for in your planner? $\endgroup$