ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to tune navigation2 for a large rectangualar holonomic robot?

asked 2020-04-20 05:36:52 -0500

Charlotteheggem gravatar image

Hi, I am trying to tune navgiation2 to work with a large, rectangular robot ( 1080 x 630 mm ). I am aware that navigation mainly is for circular robots, but I guess it should be possible to define a large robot radius to make it work with a rectangular (in my case a radius equal to the half of the diagonal = 626 mm).

When I launch navigation2 with the attached .yaml file unexpected behavior occurs. The robot seems to prefer moving backward with a diagonal heading (xy) or in y-direction (long side of robot). This is not expected as the x-velocity thresholds are higher than for xy and y. The robot rotates such that the heading of the heading of the robot is diagonal or with the y axis aligned with the path rather than exploiting the holonomic nature of the robot. Another problem that occur, is that the robot sometimes starts spinning when it is close to a goal (at the correct position, but with the wrong orientation), and aborts the goal rather than defining it as a success.

I have tried reading several guides for tuning navigation2, but as most apply for turtlebot3, I find it hard to understand what parameters must be changed for a large rectangular robot with holonomic drive. Does anyone have tips for how the parameter file can be tuned to avoid the listed problems?

I am using ROS2 Eloquent on Ubuntu 18.04, with Navigation2 built from source (master).

  amcl:
  ros__parameters:
    use_sim_time: True
    alpha1: 0.2
    alpha2: 0.2
    alpha3: 0.2
    alpha4: 0.2
    alpha5: 0.2
    base_frame_id: "base_footprint"
    beam_skip_distance: 0.5
    beam_skip_error_threshold: 0.9
    beam_skip_threshold: 0.3
    do_beamskip: false
    global_frame_id: "map"
    lambda_short: 0.1
    laser_likelihood_max_dist: 2.0
    laser_max_range: 100.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.0
    recovery_alpha_slow: 0.0
    resample_interval: 1
    robot_model_type: "omnidirectional"
    save_pose_rate: 0.5
    sigma_hit: 0.2
    tf_broadcast: true
    transform_tolerance: 1.0
    update_min_a: 0.2
    update_min_d: 0.25
    z_hit: 0.5
    z_max: 0.05
    z_rand: 0.5
    z_short: 0.05

amcl_map_client:
  ros__parameters:
    use_sim_time: True

amcl_rclcpp_node:
  ros__parameters:
    use_sim_time: True

bt_navigator:
  ros__parameters:
    use_sim_time: True
    bt_xml_filename: "navigate_w_replanning.xml"
    plugin_lib_names:
    - nav2_compute_path_to_pose_action_bt_node
    - nav2_follow_path_action_bt_node
    - nav2_back_up_action_bt_node
    - nav2_spin_action_bt_node
    - nav2_wait_action_bt_node
    - nav2_clear_costmap_service_bt_node
    - nav2_is_stuck_condition_bt_node
    - nav2_goal_reached_condition_bt_node
    - nav2_initial_pose_received_condition_bt_node
    - nav2_reinitialize_global_localization_service_bt_node
    - nav2_rate_controller_bt_node
    - nav2_recovery_node_bt_node
    - nav2_pipeline_sequence_bt_node

bt_navigator_rclcpp_node:
  ros__parameters:
    use_sim_time: True


controller_server:
  ros__parameters:
    use_sim_time: True
    controller_frequency: 20.0
    controller_plugin_types: ["dwb_core::DWBLocalPlanner"]
    controller_plugin_ids: ["FollowPath"]
    min_x_velocity_threshold: 0.0001
    min_y_velocity_threshold: 0.0001
    min_theta_velocity_threshold: 0.0001

    # DWB parameters
    FollowPath.debug_trajectory_details: True
    FollowPath.movement_time_allowance: 60.0
    FollowPath.required_movement_radius: 1.0
    FollowPath.min_vel_x: -0.3
    FollowPath.min_vel_y: -0.2
    FollowPath.max_vel_x: 0.3
    FollowPath.max_vel_y: 0.2
    FollowPath.max_vel_theta: 0.15
    FollowPath.min_speed_xy: -0.2
    FollowPath.max_speed_xy: 0.2
    FollowPath.min_speed_theta: -0.15
    FollowPath.min_x_velocity_threshold: 0.001
    FollowPath.min_y_velocity_threshold: 0.001
    FollowPath.min_theta_velocity_threshold: 0.001
    FollowPath.acc_lim_x: 1.0
    FollowPath.acc_lim_y: 1.0
    FollowPath.acc_lim_theta: 1.0
    FollowPath.decel_lim_x: -1.0
    FollowPath.decel_lim_y: -1.0
    FollowPath.decel_lim_theta: -1.0
    FollowPath.vx_samples: 20
    FollowPath.vy_samples: 20
    FollowPath.vtheta_samples: 40
    FollowPath.sim_time: 4.0
    FollowPath.linear_granularity: 0.05
    FollowPath.angular_granularity ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-07-22 04:57:43 -0500

Tahir Raseed gravatar image

Have you been able to solve it? I am also facing the same difficulty of adding a rectangular footprint of my robot.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-04-20 05:36:52 -0500

Seen: 558 times

Last updated: Jul 22 '20