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

[ERROR] [controller_server]: No valid trajectories out of 0!

asked 2020-02-18 03:44:20 -0600

lorenzo gravatar image

I am trying to run a navigation simulation with some of the nav2 packages and rviz. The node that I run are: map_server, planner_server, waypoint_follower, controller_server, recovery_server, bt_navigator. I provide also the static transform world -> map, map -> base_link (non static custom tranforsm to localize), base_link -> odom and I visualize all on rviz2. Here the main configurations:

bt_navigator:
  ros__parameters:
    bt_xml_filename: "/home/lorenzoteo/bt_navigator.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
    - nav2_round_robin_node_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.001
    min_y_velocity_threshold: 0.5
    min_theta_velocity_threshold: 0.001

# DWB parameters
FollowPath.debug_trajectory_details: True
FollowPath.min_vel_x: 0.0
FollowPath.min_vel_y: 0.0
FollowPath.max_vel_x: 0.26
FollowPath.max_vel_y: 0.0
FollowPath.max_vel_theta: 1.0
FollowPath.min_speed_xy: 0.0
FollowPath.max_speed_xy: 0.26
FollowPath.min_speed_theta: 0.0
# Add high threshold velocity for turtlebot 3 issue.
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
FollowPath.acc_lim_x: 2.5
FollowPath.acc_lim_y: 0.0
FollowPath.acc_lim_theta: 3.2
FollowPath.decel_lim_x: -2.5
FollowPath.decel_lim_y: 0.0
FollowPath.decel_lim_theta: -3.2
FollowPath.vx_samples: 20
FollowPath.vy_samples: 5
FollowPath.vtheta_samples: 20
FollowPath.sim_time: 1.7
FollowPath.linear_granularity: 0.05
FollowPath.angular_granularity: 0.025
FollowPath.transform_tolerance: 0.2
FollowPath.xy_goal_tolerance: 0.25
FollowPath.critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
FollowPath.BaseObstacle.scale: 0.02
FollowPath.PathAlign.scale: 0.0
FollowPath.GoalAlign.scale: 0.0
FollowPath.PathDist.scale: 32.0
FollowPath.GoalDist.scale: 24.0
FollowPath.RotateToGoal.scale: 32.0
FollowPath.short_circuit_trajectory_evaluation: True
FollowPath.trans_stopped_velocity: 0.25
FollowPath.slowing_factor: 5.0
FollowPath.lookahead_time: -1.0
FollowPath.stateful: True

controller_server_rclcpp_node:
  ros__parameters:
    use_sim_time: True

local_costmap:
  local_costmap:
    ros__parameters:
      update_frequency: 5.0
      publish_frequency: 2.0
      robot_base_frame: base_link
      use_sim_time: True
      global_frame: map
      rolling_window: true
      width: 3
      height: 3
      resolution: 0.05
      plugin_names: ["obstacle_layer", "voxel_layer", "inflation_layer"]
      plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
      robot_radius: 0.22
      inflation_layer:
        cost_scaling_factor: 3.0
      obstacle_layer:
        enabled: False
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      voxel_layer:
        enabled: False
        publish_voxel_map: True
        origin_z: 0.0
        z_resolution: 0.05
        z_voxels: 16
        max_obstacle_height: 2.0
        mark_threshold: 0
        observation_sources: pointcloud
        pointcloud:
          topic: /intel_realsense_r200_depth/points
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "PointCloud2"
      static_layer:
        map_subscribe_transient_local: True
      always_send_full_costmap: True
  local_costmap_client:
    ros__parameters:
      use_sim_time: True
  local_costmap_rclcpp_node:
    ros__parameters:
      use_sim_time: True

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      robot_base_frame: base_link
      global_frame: map
      use_sim_time: True
      plugin_names: ["static_layer"]
      plugin_types: ["nav2_costmap_2d::StaticLayer"]
      robot_radius: 0.22
      resolution: 0.05
      obstacle_layer:
        enabled: False
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      voxel_layer:
        enabled: False
        publish_voxel_map: True
        origin_z: 0.0
        z_resolution: 0.05
        z_voxels: 16
        max_obstacle_height: 2.0
        mark_threshold: 0
        observation_sources: pointcloud
        pointcloud:
          topic: /intel_realsense_r200_depth/points
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "PointCloud2"
      static_layer:
        map_subscribe_transient_local: True
      always_send_full_costmap: True
  global_costmap_client:
    ros__parameters:
      use_sim_time: True
  global_costmap_rclcpp_node:
    ros__parameters:
      use_sim_time: True

The result is that I obtain that message on controller server and the robot continues to spin due to robot recoveries. Why?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-02-18 12:18:51 -0600

Carl D gravatar image

This can happen if the velocity reported in your /odom data is greater than limits set in the DWB parameters. In your case, if the X velocity exceeds FollowPath.max_vel_x or (Sqrt(X^2 + Y^2) exceeds FollowPath.max_speed_xy

edit flag offensive delete link more

Comments

"This can happen if the velocity reported in your /odom data" what do you mean? The odom frame is fixed and coincident with base_link. The base_link moves accordingly with integration over time of cmd_vel. I tried to modify the following parameters accordingly to your suggestions, but doesn't work.

FollowPath.max_vel_x: 0.26
FollowPath.max_speed_xy: 0.3 #now is greater than sqrt(x^2 + y^2)

The following are further console output that maybe could be useful for you to understand:

[INFO] [global_costmap.global_costmap]: Received request to clear entirely the global_costmap
[INFO] [local_costmap.local_costmap]: Received request to clear entirely the local_costmap

It seems that the costmaps built are "occupied".

lorenzo gravatar image lorenzo  ( 2020-02-19 02:18:19 -0600 )edit

It seems that the costmaps built are "occupied".

That is just the default behavior when DWB fails. We just try to clear the costmaps regardless of the reason for failure. That is something we need to improve on. It is unrelated to the real problem.

What I recommend is running rqt, going to Plugins->Visualization->plot and monitoring the /odom topic - specifically you want to monitor the following fields in the message

  • twist/twist/linear/x
  • twist/twist/linear/y
  • twist/twist/angular/z

My guess is that one or more of the fields above will be very noisy and go beyond the maximum values.

Carl D gravatar image Carl D  ( 2020-02-19 10:57:20 -0600 )edit

On the /odom topic is not published anything.

lorenzo gravatar image lorenzo  ( 2020-02-19 11:19:05 -0600 )edit

Oh. Well, that is a problem. The controller uses the /odom messages to determine the current velocity of the robot. Without that, information, it will be unable to plan properly.

The /odom message is normally published by the gazebo diff_drive plugin (or equivalent). On a real robot, it is published by the robot base controller - typically a node that reads the IMU or wheel encoders.

Carl D gravatar image Carl D  ( 2020-02-19 11:31:21 -0600 )edit

What is the meaning of the header frame id and the child frame id in that topic?

lorenzo gravatar image lorenzo  ( 2020-02-19 15:04:52 -0600 )edit

Usually, header frame id is odom and child_frame_id is base_footprint or base_link.

Basically, the /odom message gives the position and velocity of the robot in relation to the odom frame, so the child_frame_id is the frame of reference used by the robot. If you follow the standard https://www.ros.org/reps/rep-0105.html, then it should be base_link, but for variious reasons, the example configuration provided by Nav2 uses base_footprint

Carl D gravatar image Carl D  ( 2020-02-19 15:50:02 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2020-02-18 03:44:20 -0600

Seen: 993 times

Last updated: Feb 18 '20