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

[ROS2] collision avoidance(without map) using dwb_controller in navigation2

asked 2019-09-02 19:47:25 -0500

Darby Lim gravatar image

updated 2019-09-02 19:48:14 -0500

I have tried to collision avoidance(without map) using dwb_controller in navigation2 package (ROS2 Dashing)

I have launched turtlebot3_gazebo and nav2_navigation.launch.py.

$ ros2 launch nav2_bringup nav2_navigation_launch.py use_sim_time:=True autostart:=True

Every packages was launched successfully but TurtleBot3 was not moved when I publish goal pose using below command

$ ros2 topic pub /move_base_simple/goal geometry_msgs/PoseStamped "{header: {stamp: {sec: 0}, frame_id: 'odom'}, pose: {position: {x: 0.2, y: 0.0, z: 0.0}, orientation: {w: 1.0}}}"

I have attached log lines when I launched navigation2 packages

[INFO] [launch]: All log files can be found below /home/.....
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [world_model-1]: process started with pid [13672]
[INFO] [dwb_controller-2]: process started with pid [13673]
[INFO] [navfn_planner-3]: process started with pid [13674]
[INFO] [recoveries_node-4]: process started with pid [13675]
[INFO] [bt_navigator-5]: process started with pid [13676]
[INFO] [lifecycle_manager-6]: process started with pid [13677]
[lifecycle_manager-6] [INFO] [lifecycle_manager_control]: Creating
[lifecycle_manager-6] [INFO] [lifecycle_manager_control]: Starting the system bringup...
[lifecycle_manager-6] [INFO] [lifecycle_manager_control]: Creating and initializing lifecycle service clients
[world_model-1] [INFO] [world_model]: Creating
[lifecycle_manager-6] [INFO] [lifecycle_manager_control]: Configuring and activating world_model
[dwb_controller-2] [INFO] [dwb_controller]: Creating
[bt_navigator-5] [INFO] [bt_navigator]: Creating
[recoveries_node-4] [INFO] [recoveries]: Configuring Spin
[world_model-1] [INFO] [global_costmap.global_costmap]: Creating
[recoveries_node-4] [WARN] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.
[recoveries_node-4] [INFO] [recoveries]: Configuring BackUp
[dwb_controller-2] [INFO] [local_costmap.local_costmap]: Creating
[navfn_planner-3] [INFO] [navfn_planner]: Creating
[world_model-1] [INFO] [world_model]: Configuring
[world_model-1] [INFO] [global_costmap.global_costmap]: Configuring
[world_model-1] [INFO] [global_costmap.global_costmap]: Using plugin "static_layer"
[world_model-1] [INFO] [global_costmap.global_costmap]: Using plugin "obstacle_layer"
[world_model-1] [INFO] [global_costmap.global_costmap]: Subscribed to Topics: scan
[world_model-1] [INFO] [global_costmap.global_costmap]: Using plugin "inflation_layer"
[world_model-1] [INFO] [world_model]: Activating
[world_model-1] [INFO] [global_costmap.global_costmap]: Activating
[world_model-1] [INFO] [global_costmap.global_costmap]: Checking transform
[world_model-1] [INFO] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: . canTransform returned after 12.954 timeout was 1.
[world_model-1] [INFO] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: . canTransform returned after 1.003 timeout was 1.
[world_model-1] [INFO] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: . canTransform returned after 1.003 timeout was 1.
[world_model-1] [INFO] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: . canTransform returned after 1.094 timeout was 1.
[world_model-1] [INFO] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: . canTransform returned after 1.097 timeout was 1.
[world_model-1] [INFO] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: . canTransform returned after 1.098 timeout was 1.
[world_model-1] [INFO] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2021-06-22 15:06:21 -0500

charlie92 gravatar image

updated 2021-06-22 15:09:29 -0500

2 years late but anyone trying this must provide, as described in stevemacenski's comment, the map->odom identity transform. This can be done with tf2_ros package:

ros2 run tf2_ros static_transform_publisher 0 0 0 0 0 0  map odom

You'll also need to modify the global_costmap in params.yaml to have rolling_window: True since you are not using any map. Also provide the window size, in my case 20x20 worked well. Also don't use the static layer since it does not make sense because there is no map. Then you are ready to send any goal.

For example the global_costmap can look like:

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: odom
      robot_base_frame: chassis
      use_sim_time: True
      rolling_window: True
      width: 20
      height: 20
      robot_radius: 0.5
      resolution: 0.05
      track_unknown_space: true
      plugins: ["obstacle_layer", "inflation_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
          obstacle_range: 10.0
          raytrace_range:  10.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 0.4
edit flag offensive delete link more
0

answered 2019-09-03 17:48:01 -0500

updated 2019-09-03 17:51:05 -0500

The error is what it seems,

Timed out waiting for transform from base_link to map to become available, tf error: . canTransform returned after 12.954 timeout was 1.

You haven't provided a complete base_link -> map transformation. We currently don't provide an identity transform on bringup for map->odom that AMCL or SLAM will provide, so you need to use the 2D pose estimator tool in rviz (or ros2 topic pub on the topic) to get it to have an initial transformation.

Edit: we recently merged something that'll let you set it from parameter files too https://github.com/ros-planning/navig...

edit flag offensive delete link more

Comments

If I haven't provided a complete base_link->map tf, I wouldn't use navigation2? I just wanna turtlebot3 explore space with some static objects.

Darby Lim gravatar image Darby Lim  ( 2019-09-16 05:53:55 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-09-02 19:47:25 -0500

Seen: 553 times

Last updated: Jun 22 '21