Skip to content

Mppi: Strange behavior with Controller acceleration #5579

@MateoGarciaSubiran

Description

@MateoGarciaSubiran

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • Computer:
    • Intel Celeron J6412 2.00Ghz 16GB memory
  • ROS2 Version:
    • Humble binaries
    • Nav2 humble_main
  • Version or commit hash:
  • DDS implementation:
    • default
  • Nav2 Package:
    • MPPI
  • Have you asked this on Robotics Stack Exchange?
    • No

Tuning / Configuration Goal

Hello, I am trying to configure my real robot so that it can navigate from its position to a specific point.
To do this, I have set the actual speeds and accelerations that my robot can handle.

What I've Tried

Description:
I followed the steps to configure the MPPI according to the notes in the documentation, and in the first test I saw that my robot is able to follow the path and navigate, but it goes past its destination. At first, I thought it was an issue related to the horizon and the aspects mentioned in the user notes, but after conducting more in-depth research, I see that the robot is only able to reach its destination accurately if I set very high linear and angular accelerations that are not the robot's actual ones.

The configuration with the actual limitations of the robot is as follows:

controller_server:
  ros__parameters:
    use_sim_time: false
    controller_frequency: 20.0
    min_x_velocity_threshold: 0.001
    min_y_velocity_threshold: 0.001
    min_theta_velocity_threshold: 0.001
    failure_tolerance: 0.3
    progress_checker_plugin: "progress_checker"
    goal_checker_plugins: ["precise_goal_checker"] # "precise_goal_checker"
    controller_plugins: ["FollowPath"]
    speed_limit_topic: "/speed_limit" 
    odom_topic: "/odometry/filtered"
    publish_critics_stats: true
    # Progress checker parameters
    progress_checker:
      plugin: "nav2_controller::SimpleProgressChecker"
      required_movement_radius: 0.0
      movement_time_allowance: 10.0
    # Goal checker parameters
    precise_goal_checker:
      plugin: "nav2_controller::SimpleGoalChecker"
      xy_goal_tolerance: 0.4
      yaw_goal_tolerance: 0.2
      stateful: False
    general_goal_checker:
      stateful: True
      plugin: "nav2_controller::SimpleGoalChecker"
      xy_goal_tolerance: 0.15
      yaw_goal_tolerance: 0.20
    # MPPI
    FollowPath:
      plugin: "nav2_mppi_controller::MPPIController"
      time_steps: 56
      model_dt: 0.05
      batch_size: 1000
      vx_std: 0.27
      vy_std: 0.0
      wz_std: 0.15
      vx_max: 0.8
      vx_min: -0.8
      vy_max: 0.0
      wz_max: 0.3
      ax_max: 0.7
      ax_min: -0.7
      ay_min: -0.0
      ay_max: 0.0
      az_max: 1.75
      iteration_count: 1
      
      # prune_distance: 4.06
      prune_distance: 2.3
      
      transform_tolerance: 0.1
      temperature: 0.3
      gamma: 0.015
      motion_model: "DiffDrive"
      visualize: false
      reset_period: 1.0 # (only in Humble)
      regenerate_noises: false
      publish_optimal_trajectory: true
      enforce_path_inversion: false
      TrajectoryVisualizer:
        trajectory_step: 5
        time_step: 3
      TrajectoryValidator:
        plugin: "mppi::DefaultOptimalTrajectoryValidator"
        collision_lookahead_time: 2.0
        
        # consider_footprint: false
        consider_footprint: true
        
      AckermannConstraints:
        min_turning_r: 0.2
      
      critics: ["ConstraintCritic", "CostCritic", "GoalCritic", "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic", "PathAngleCritic", "PreferForwardCritic"]
      #critics: ["ConstraintCritic","GoalCritic", "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic", "PathAngleCritic"]
      
      ConstraintCritic:
        enabled: true
        cost_power: 1
        cost_weight: 4.0
      GoalCritic:
        enabled: true
        cost_power: 1
        cost_weight: 5.0
        threshold_to_consider: 2.3
      GoalAngleCritic:
        enabled: true
        cost_power: 1
        cost_weight: 3.0
        threshold_to_consider: 2.3
      PreferForwardCritic:
        enabled: false
        cost_power: 1
        cost_weight: 5.0
        threshold_to_consider: 2.3
      ObstaclesCritic:
        enabled: false
        cost_power: 1
        repulsion_weight: 0.6
        critical_weight: 20.0
        consider_footprint: false
        collision_cost: 100000.0
        collision_margin_distance: 0.1
        near_goal_distance: 0.5
        inflation_radius: 2.0 # (only in Humble)
        cost_scaling_factor: 3.0 # (only in Humble)
      CostCritic:
        enabled: true
        cost_power: 1
        cost_weight: 3.81
        critical_cost: 300.0
        consider_footprint: false
        collision_cost: 1000000.0
        near_goal_distance: 0.5
        trajectory_point_step: 2
      PathAlignCritic:
        enabled: true
        cost_power: 1
        cost_weight: 14.0
        max_path_occupancy_ratio: 0.05
        trajectory_point_step: 4
        threshold_to_consider: 2.3
        offset_from_furthest: 20
        use_path_orientations: false
      PathFollowCritic:
        enabled: true
        cost_power: 1
        cost_weight: 5.0
        offset_from_furthest: 5
        threshold_to_consider: 2.3
      PathAngleCritic:
        enabled: true
        cost_power: 1
        cost_weight: 2.0
        offset_from_furthest: 4
        threshold_to_consider: 2.3
        max_angle_to_furthest: 1.0
        mode: 1
      # VelocityDeadbandCritic:
      #   enabled: true
      #   cost_power: 1
      #   cost_weight: 35.0
      #   deadband_velocities: [0.05, 0.05, 0.05]
      # TwirlingCritic:
      #   enabled: true
      #   twirling_cost_power: 1
      #   twirling_cost_weight: 10.0
local_costmap:
  local_costmap:
    ros__parameters:
      update_frequency: 4.0
      publish_frequency: 2.0
      global_frame: odom
      robot_base_frame: base_link
      use_sim_time: false
      rolling_window: true
      width: 9
      height: 9
      resolution: 0.03
      robot_radius: 1.15
      #footprint: "[[0.800, 0.800], [-0.800, 0.800], [-0.800, -0.800], [0.800, -0.800]]"
      plugins: ["obstacle_layer", "inflation_layer"]
      # plugins: ["voxel_layer","obstacle_layer", "inflation_layer", "exclusive_layer"]
      filters: ["keepout_filter", "speed_filter"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 2.0
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        footprint_clearing_enabled: true
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 50.0
          raytrace_min_range: 0.0
          obstacle_max_range: 10.0
          obstacle_min_range: 0.0
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
      always_send_full_costmap: True     
      keepout_filter:
        plugin: "nav2_costmap_2d::KeepoutFilter"
        enabled: True
        filter_info_topic: "keepout_costmap_filter_info"
        override_lethal_cost: True
        lethal_override_cost: 200           
      speed_filter:
        plugin: "nav2_costmap_2d::SpeedFilter"
        enabled: False
        filter_info_topic: "speed_costmap_filter_info"
        speed_limit_topic: "speed_limit"

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: map
      robot_base_frame: base_link
      use_sim_time: false
      robot_radius: 1.15
      resolution: 0.03
      track_unknown_space: false
      plugins: ["static_layer","obstacle_layer","inflation_layer"]
      filters: ["keepout_filter","inflation_layer", "exclusive_layer"]
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        footprint_clearing_enabled: true
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 50.0
          raytrace_min_range: 0.0
          obstacle_max_range: 10.0
          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: 2.0
      always_send_full_costmap: True
      keepout_filter:
        plugin: "nav2_costmap_2d::KeepoutFilter"
        enabled: True
        filter_info_topic: "keepout_costmap_filter_info"
        override_lethal_cost: True
        lethal_override_cost: 200
      exclusive_layer:
        plugin: "nav2_costmap_2d::ExclusiveLayer"
        enabled: true
        directional_map_file: "/root/MecaluxFileSystem/Maps/Current/GeneralCostmap/FixedDirectionZones.dat"
        local_layer: true
        map_frame: map
        transform_tolerance: 0.1
        debug_mode: false

If we calculate the accelerations that the robot receives when navigating with this configuration, we see that it never reaches the maximum we are asking for, and this results in the behavior described above.

errorNavigation.mp4

The blue line is barely visible, but it coincides with the red line, which is the speed that is ultimately transferred to the engines.
Image

With this configuration, I would expect to see calculated accelerations of around 0.6 or 0.7 when braking or starting to navigate.

If we change ax_max to 3.0, ax_min to 3.0, and aw_max to 3.5, we see that it achieves higher accelerations, which are what I would expect it to achieve with the “correct/real” configuration.

correcNavigation.mp4
Image

I don't know if I have something configured incorrectly, but I assumed it was a matter of acceleration because with that change it is now able to meet all the objectives we asked for.
Thank you very much.

Metadata

Metadata

Assignees

No one assigned

    Labels

    questionFurther information is requested

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions