[Closed] Rosbot 2.0 Pro navigation with namespace failed under ROS Melodic

Hi,

with your help in here, I did successfully run my rosbot 2.0 pro in namespace under ROS Kinetic. here is my repository launch_rosbot.

Recently, I updated my rosbot 2.0 pro from ROS Kinetic to Melodic, and then it failed!!!

Here is what I did:

  • I started roscore and map_server at a master node
  • I started my rosbot by roslaunch launch_rosbot launch_rosbot_with_name.launch

Then, I will get warning like:

Warning: Invalid argument “/map” passed to canTransform argument target_frame in tf2 frame_ids cannot start with a ‘/’ like:
at line 134 in /tmp/binarydeb/ros-melodic-tf2-0.6.5/src/buffer_core.cpp

and TF tree will not build successfully, it looks like:

Could you please help to have a check? So Thanks!

BRs,
Si

Hi,
This error is due to lines 11-13 in your launch file. This replacement should fix the problem:

    <arg name="odom_frame_id"   default="$(arg robot_namespace)/odom"/>
    <arg name="base_frame_id"   default="$(arg robot_namespace)/base_link"/>
    <arg name="global_frame_id" default="map"/>

I’m afraid that it is also necessary to change the serial_baudrate value in this line to 525000.

Make sure you are using the latest rosbot_ekf and the latest firmware (0.15.0) for Melodic.
Please, let me know about it. If you have any questions/troubles, do not hesitate to ask.

Best regards,
Paweł

Hi, Paweł,

Thanks so much for your help!

I think I am using the latest rosbot_ekf for I upgraded my Rosbot 2.0 pro system with the image * Ubuntu 18.04 + ROS Melodic + Docker + Husarnet client and followed the reinstallation guidance of ROSbot 2.0 PRO, and I also did relashed the firmaware as the following.

But I found a weird thing that the rosbot_ekf is still using 460800 as the serial_baudrate, you can find it in the output after I run roslaunch rosbot_ekf all.launch rosbot_pro:=true,


and a warning [ WARN] [1649838454.832404604]: Transform from imu_link to base_link was unavailable for the time requested. Using latest instead. keeps pop out.

If I change serial_baudrate to 508000 in my scripts in my start_namesapce.launch in which I updated line 11-13 as your suggested and also remove the start / from line 17, there will be an error promt [ERROR] [1649837529.985029]: Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino after I run my own scripts launch_rosbot_with_name.launch

Here is the full log when I use 525000 as the value of serial_baudrate,

... logging to /home/husarion/.ros/log/ae346176-bb00-11ec-8fcc-000c297f8939/roslaunch-husarion-28361.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://192.168.124.25:46051/

SUMMARY
========

CLEAR PARAMETERS
 * /rosbot1/rosbot_ekf/

PARAMETERS
 * /rosbot1/amcl/base_frame_id: /rosbot1/base_link
 * /rosbot1/amcl/global_frame_id: map
 * /rosbot1/amcl/initial_pose_x: 0.0
 * /rosbot1/amcl/initial_pose_y: 0.0
 * /rosbot1/amcl/initial_pose_z: 0.0
 * /rosbot1/amcl/max_particles: 5000
 * /rosbot1/amcl/min_particles: 1000
 * /rosbot1/amcl/odom_frame_id: /rosbot1/odom
 * /rosbot1/amcl/odom_model_type: diff-corrected
 * /rosbot1/amcl/update_min_a: 1.0
 * /rosbot1/amcl/update_min_d: 0.1
 * /rosbot1/amcl/use_map_topic: True
 * /rosbot1/move_base_rosbot/DWAPlannerROS/global_frame_id: rosbot1/odom
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_Y: 1.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_theta: 5.0
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_x: 1.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/holonomic_robot: False
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/max_vel_theta: 2.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/max_vel_x: 0.1
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/meter_scoring: True
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_in_place_vel_theta: 0.25
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_vel_theta: -2.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_vel_x: 0.01
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/xy_goal_tolerance: 0.1
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/yaw_goal_tolerance: 0.05
 * /rosbot1/move_base_rosbot/global_costmap/\obstacle_range: 6.0
 * /rosbot1/move_base_rosbot/global_costmap/always_send_full_costmap: True
 * /rosbot1/move_base_rosbot/global_costmap/footprint: [[0.12, 0.14], [0...
 * /rosbot1/move_base_rosbot/global_costmap/global_frame: map
 * /rosbot1/move_base_rosbot/global_costmap/height: 25
 * /rosbot1/move_base_rosbot/global_costmap/inflation_radius: 2.5
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/clearing: True
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/data_type: LaserScan
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/marking: True
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/sensor_frame: rosbot1/laser
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/topic: /rosbot1/scan
 * /rosbot1/move_base_rosbot/global_costmap/map_topic: map
 * /rosbot1/move_base_rosbot/global_costmap/observation_sources: laser_scan_sensor
 * /rosbot1/move_base_rosbot/global_costmap/publish_frequency: 0.5
 * /rosbot1/move_base_rosbot/global_costmap/raytrace_range: 8.5
 * /rosbot1/move_base_rosbot/global_costmap/resolution: 0.01
 * /rosbot1/move_base_rosbot/global_costmap/robot_base_frame: rosbot1/base_link
 * /rosbot1/move_base_rosbot/global_costmap/rolling_window: True
 * /rosbot1/move_base_rosbot/global_costmap/static_map: True
 * /rosbot1/move_base_rosbot/global_costmap/subscribe_to_updates: True
 * /rosbot1/move_base_rosbot/global_costmap/transform_tolerance: 0.8
 * /rosbot1/move_base_rosbot/global_costmap/update_frequency: 0.5
 * /rosbot1/move_base_rosbot/global_costmap/width: 50
 * /rosbot1/move_base_rosbot/local_costmap/\obstacle_range: 6.0
 * /rosbot1/move_base_rosbot/local_costmap/always_send_full_costmap: True
 * /rosbot1/move_base_rosbot/local_costmap/footprint: [[0.12, 0.14], [0...
 * /rosbot1/move_base_rosbot/local_costmap/global_frame: rosbot1/odom
 * /rosbot1/move_base_rosbot/local_costmap/height: 3
 * /rosbot1/move_base_rosbot/local_costmap/inflation_radius: 1.0
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/clearing: True
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/data_type: LaserScan
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/marking: True
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/sensor_frame: rosbot1/laser
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/topic: /rosbot1/scan
 * /rosbot1/move_base_rosbot/local_costmap/map_topic: map
 * /rosbot1/move_base_rosbot/local_costmap/observation_sources: laser_scan_sensor
 * /rosbot1/move_base_rosbot/local_costmap/origin_x: -1.5
 * /rosbot1/move_base_rosbot/local_costmap/origin_y: -1.5
 * /rosbot1/move_base_rosbot/local_costmap/publish_frequency: 5
 * /rosbot1/move_base_rosbot/local_costmap/raytrace_range: 8.5
 * /rosbot1/move_base_rosbot/local_costmap/resolution: 0.01
 * /rosbot1/move_base_rosbot/local_costmap/robot_base_frame: rosbot1/base_link
 * /rosbot1/move_base_rosbot/local_costmap/rolling_window: True
 * /rosbot1/move_base_rosbot/local_costmap/static_map: True
 * /rosbot1/move_base_rosbot/local_costmap/subscribe_to_updates: True
 * /rosbot1/move_base_rosbot/local_costmap/transform_tolerance: 0.25
 * /rosbot1/move_base_rosbot/local_costmap/update_frequency: 5
 * /rosbot1/move_base_rosbot/local_costmap/width: 3
 * /rosbot1/rosbot_ekf/acceleration_gains: [0.8, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/acceleration_limits: [1.3, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/base_link_frame: base_link
 * /rosbot1/rosbot_ekf/control_config: [True, False, Fal...
 * /rosbot1/rosbot_ekf/control_timeout: 0.2
 * /rosbot1/rosbot_ekf/debug: False
 * /rosbot1/rosbot_ekf/debug_out_file: /path/to/debug/fi...
 * /rosbot1/rosbot_ekf/deceleration_gains: [1.0, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/deceleration_limits: [1.3, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/frequency: 20
 * /rosbot1/rosbot_ekf/imu0: imu
 * /rosbot1/rosbot_ekf/imu0_config: [False, False, Fa...
 * /rosbot1/rosbot_ekf/imu0_differential: True
 * /rosbot1/rosbot_ekf/imu0_linear_acceleration_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/imu0_nodelay: False
 * /rosbot1/rosbot_ekf/imu0_pose_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/imu0_queue_size: 4
 * /rosbot1/rosbot_ekf/imu0_relative: True
 * /rosbot1/rosbot_ekf/imu0_remove_gravitational_acceleration: True
 * /rosbot1/rosbot_ekf/imu0_twist_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/initial_estimate_covariance: ['1e-9', 0, 0, 0,...
 * /rosbot1/rosbot_ekf/map_frame: map
 * /rosbot1/rosbot_ekf/odom0: odom/wheel
 * /rosbot1/rosbot_ekf/odom0_config: [True, True, True...
 * /rosbot1/rosbot_ekf/odom0_differential: False
 * /rosbot1/rosbot_ekf/odom0_nodelay: False
 * /rosbot1/rosbot_ekf/odom0_queue_size: 6
 * /rosbot1/rosbot_ekf/odom0_relative: True
 * /rosbot1/rosbot_ekf/odom_frame: odom
 * /rosbot1/rosbot_ekf/print_diagnostics: True
 * /rosbot1/rosbot_ekf/process_noise_covariance: [0.05, 0, 0, 0, 0...
 * /rosbot1/rosbot_ekf/publish_acceleration: False
 * /rosbot1/rosbot_ekf/publish_tf: True
 * /rosbot1/rosbot_ekf/sensor_timeout: 0.2
 * /rosbot1/rosbot_ekf/stamped_control: False
 * /rosbot1/rosbot_ekf/transform_time_offset: 0.0
 * /rosbot1/rosbot_ekf/transform_timeout: 0.0
 * /rosbot1/rosbot_ekf/two_d_mode: False
 * /rosbot1/rosbot_ekf/use_control: True
 * /rosbot1/rosbot_ekf/world_frame: odom
 * /rosbot1/rplidar/angle_compensate: True
 * /rosbot1/rplidar/frame_id: /rosbot1/laser
 * /rosbot1/rplidar/serial_baudrate: 256000
 * /rosbot1/rplidar/tf_prefix: rosbot1
 * /rosbot1/serial_node/baud: 525000
 * /rosbot1/serial_node/port: /dev/ttyS4
 * /rosdistro: melodic
 * /rosversion: 1.14.10

NODES
  /rosbot1/
    amcl (amcl/amcl)
    imu_publisher (tf/static_transform_publisher)
    laser_broadcaster (tf/static_transform_publisher)
    move_base_rosbot (move_base/move_base)
    msgs_conversion (rosbot_ekf/msgs_conversion)
    rosbot_ekf (robot_localization/ekf_localization_node)
    rplidar (rplidar_ros/rplidarNode)
    serial_node (rosserial_python/serial_node.py)

ROS_MASTER_URI=http://192.168.124.39:11311

process[rosbot1/rplidar-1]: started with pid [28564]
process[rosbot1/serial_node-2]: started with pid [28566]
process[rosbot1/msgs_conversion-3]: started with pid [28577]
process[rosbot1/rosbot_ekf-4]: started with pid [28580]
process[rosbot1/imu_publisher-5]: started with pid [28581]
process[rosbot1/laser_broadcaster-6]: started with pid [28591]
process[rosbot1/amcl-7]: started with pid [28607]
process[rosbot1/move_base_rosbot-8]: started with pid [28615]
[ WARN] [1649837512.026224423]: Both imu0_differential and imu0_relative were set to true. Using differential mode.
[ WARN] [1649837512.295228568]: ignoring NAN in initial pose Yaw
[ INFO] [1649837512.488338031]: Subscribed to map topic.
[INFO] [1649837512.799668]: ROS Serial Python Node
[INFO] [1649837512.847558]: Connecting to /dev/ttyS4 at 525000 baud
[INFO] [1649837514.977152]: Requesting topics...
[ WARN] [1649837517.422660232]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100158 timeout was 0.1.
[ WARN] [1649837522.468475319]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.101105 timeout was 0.1.
[ WARN] [1649837527.501984393]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.10095 timeout was 0.1.
[ WARN] [1649837527.997069397]: No laser scan received (and thus no pose updates have been published) for 1649837527.996922 seconds.  Verify that data is being published on the /rosbot1/scan topic.
[ERROR] [1649837529.985029]: Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino

After I restore the serial_baudrate as 460800, the [ERROR] [1649837529.985029]: Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino will dispear, but the warnings about tf error and no laser scan recieved are still there,

[ WARN] [1649839825.251990027]: Could not obtain transform from imu_link to base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1649839826.739516513]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100976 timeout was 0.1.
[ WARN] [1649839827.351328523]: Could not obtain transform from imu_link to base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1649839829.351358318]: Could not obtain transform from imu_link to base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1649839831.351481280]: Could not obtain transform from imu_link to base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1649839831.884934991]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100317 timeout was 0.1.
[ WARN] [1649839836.920249014]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100835 timeout was 0.1.
[ WARN] [1649839837.151363684]: Could not obtain transform from imu_link to base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1649839837.304792733]: No laser scan received (and thus no pose updates have been published) for 1649839837.304642 seconds.  Verify that data is being published on the /rosbot1/scan topic.

the TF tree is still like before,

Waiting for your guidance and Thanks in advance!

BRs,
Si

Hi,
I’m afarid you firmware version is incompatible with your rosbot_ekf package. Just to be 100% sure, please flash the latest firmware version (0.15.0). There are two possibilities:

  • try to build the PlatformIO project and flash firmware using stm32loader (github repo with instruction), or,
  • use our Docker image, which allows you to easily build and upload the latest firmware version. It’s just one command and a few minutes of waiting (github report with instruction)

Also replace your ekf package with its latest version.

Please, let me know about it. If you have any questions/troubles, do not hesitate to ask.

Best regards,
Paweł

Hi, Pkowalsk,

Thanks a lot for your great help!

With you guidance, I succesfully update my firmware and rosbot_ekf package, here is some logs after roslaunch rosbot_ekf all.launch rosbot_pro:=true,

husarion@husarion:~/husarion_ws$ roslaunch rosbot_ekf all.launch rosbot_pro:=true
... logging to /home/husarion/.ros/log/ae346176-bb00-11ec-8fcc-000c297f8939/roslaunch-husarion-1967.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://192.168.124.25:33915/

SUMMARY
========

CLEAR PARAMETERS
 * /rosbot_ekf/

PARAMETERS
......
  * /rosdistro: melodic
 * /rosversion: 1.14.10
 * /serial_node/baud: 525000
 * /serial_node/port: /dev/ttyS4

......
[INFO] [1650245981.916345]:

 ______  _____  _____  _             _           __
 | ___ \|  _  |/  ___|| |           | |         / _|
 | |_/ /| | | |\ `--. | |__    ___  | |_       | |_ __      __
 |    / | | | | `--. \| '_ \  / _ \ | __|      |  _|\ \ /\ / /
 | |\ \ \ \_/ //\__/ /| |_) || (_) || |_       | |   \ V  V /
 \_| \_| \___/ \____/ |_.__/  \___/  \__|      |_|    \_/\_/

 Firmware version: 0.15.0


[INFO] [1650245981.926885]: Detected sensor: MPU9250

But now I am still stuck in building the correct tf tree for navigation with robot namespace. Here are my steps:

  1. launch roscore and map server in another host
  2. launch my own scripts to support localization and navigation via file launch_rosbot_with_name.launch, which also involves start_namesapce.launch

After that, I will get warnings like,

[ WARN] [1650255759.606458809]: Could not obtain transform from odom to rosbot1/odom. Error was “rosbot1/odom” passed to lookupTransform argument target_frame does not exist.
[ WARN] [1650255765.656814882]: Could not obtain transform from imu_link to rosbot1/base_link. Error was “imu_link” passed to lookupTransform argument source_frame does not exist.
[ WARN] [1650255766.086621613]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist… canTransform returned after 0.100278 timeout was 0.1.

here is the full logs for your reference,

... logging to /home/husarion/.ros/log/ae346176-bb00-11ec-8fcc-000c297f8939/roslaunch-husarion-10625.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://192.168.124.25:44147/

SUMMARY
========

CLEAR PARAMETERS
 * /rosbot1/rosbot_ekf/

PARAMETERS
 * /rosbot1/amcl/base_frame_id: /rosbot1/base_link
 * /rosbot1/amcl/global_frame_id: map
 * /rosbot1/amcl/initial_pose_x: 0.0
 * /rosbot1/amcl/initial_pose_y: 0.0
 * /rosbot1/amcl/initial_pose_z: 0.0
 * /rosbot1/amcl/max_particles: 5000
 * /rosbot1/amcl/min_particles: 1000
 * /rosbot1/amcl/odom_frame_id: /rosbot1/odom
 * /rosbot1/amcl/odom_model_type: diff-corrected
 * /rosbot1/amcl/update_min_a: 1.0
 * /rosbot1/amcl/update_min_d: 0.1
 * /rosbot1/amcl/use_map_topic: True
 * /rosbot1/move_base_rosbot/DWAPlannerROS/global_frame_id: rosbot1/odom
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_Y: 1.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_theta: 5.0
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_x: 1.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/holonomic_robot: False
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/max_vel_theta: 2.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/max_vel_x: 0.1
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/meter_scoring: True
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_in_place_vel_theta: 0.25
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_vel_theta: -2.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_vel_x: 0.01
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/xy_goal_tolerance: 0.1
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/yaw_goal_tolerance: 0.05
 * /rosbot1/move_base_rosbot/global_costmap/\obstacle_range: 6.0
 * /rosbot1/move_base_rosbot/global_costmap/always_send_full_costmap: True
 * /rosbot1/move_base_rosbot/global_costmap/footprint: [[0.12, 0.14], [0...
 * /rosbot1/move_base_rosbot/global_costmap/global_frame: map
 * /rosbot1/move_base_rosbot/global_costmap/height: 25
 * /rosbot1/move_base_rosbot/global_costmap/inflation_radius: 2.5
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/clearing: True
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/data_type: LaserScan
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/marking: True
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/sensor_frame: rosbot1/laser
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/topic: /rosbot1/scan
 * /rosbot1/move_base_rosbot/global_costmap/map_topic: map
 * /rosbot1/move_base_rosbot/global_costmap/observation_sources: laser_scan_sensor
 * /rosbot1/move_base_rosbot/global_costmap/publish_frequency: 0.5
 * /rosbot1/move_base_rosbot/global_costmap/raytrace_range: 8.5
 * /rosbot1/move_base_rosbot/global_costmap/resolution: 0.01
 * /rosbot1/move_base_rosbot/global_costmap/robot_base_frame: rosbot1/base_link
 * /rosbot1/move_base_rosbot/global_costmap/rolling_window: True
 * /rosbot1/move_base_rosbot/global_costmap/static_map: True
 * /rosbot1/move_base_rosbot/global_costmap/subscribe_to_updates: True
 * /rosbot1/move_base_rosbot/global_costmap/transform_tolerance: 0.8
 * /rosbot1/move_base_rosbot/global_costmap/update_frequency: 0.5
 * /rosbot1/move_base_rosbot/global_costmap/width: 50
 * /rosbot1/move_base_rosbot/local_costmap/\obstacle_range: 6.0
 * /rosbot1/move_base_rosbot/local_costmap/always_send_full_costmap: True
 * /rosbot1/move_base_rosbot/local_costmap/footprint: [[0.12, 0.14], [0...
 * /rosbot1/move_base_rosbot/local_costmap/global_frame: rosbot1/odom
 * /rosbot1/move_base_rosbot/local_costmap/height: 3
 * /rosbot1/move_base_rosbot/local_costmap/inflation_radius: 1.0
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/clearing: True
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/data_type: LaserScan
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/marking: True
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/sensor_frame: rosbot1/laser
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/topic: /rosbot1/scan
 * /rosbot1/move_base_rosbot/local_costmap/map_topic: map
 * /rosbot1/move_base_rosbot/local_costmap/observation_sources: laser_scan_sensor
 * /rosbot1/move_base_rosbot/local_costmap/origin_x: -1.5
 * /rosbot1/move_base_rosbot/local_costmap/origin_y: -1.5
 * /rosbot1/move_base_rosbot/local_costmap/publish_frequency: 5
 * /rosbot1/move_base_rosbot/local_costmap/raytrace_range: 8.5
 * /rosbot1/move_base_rosbot/local_costmap/resolution: 0.01
 * /rosbot1/move_base_rosbot/local_costmap/robot_base_frame: rosbot1/base_link
 * /rosbot1/move_base_rosbot/local_costmap/rolling_window: True
 * /rosbot1/move_base_rosbot/local_costmap/static_map: True
 * /rosbot1/move_base_rosbot/local_costmap/subscribe_to_updates: True
 * /rosbot1/move_base_rosbot/local_costmap/transform_tolerance: 0.25
 * /rosbot1/move_base_rosbot/local_costmap/update_frequency: 5
 * /rosbot1/move_base_rosbot/local_costmap/width: 3
 * /rosbot1/rosbot_ekf/acceleration_gains: [0.8, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/acceleration_limits: [1.3, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/base_link_frame: rosbot1/base_link
 * /rosbot1/rosbot_ekf/control_config: [True, False, Fal...
 * /rosbot1/rosbot_ekf/control_timeout: 0.2
 * /rosbot1/rosbot_ekf/debug: False
 * /rosbot1/rosbot_ekf/debug_out_file: /path/to/debug/fi...
 * /rosbot1/rosbot_ekf/deceleration_gains: [1.0, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/deceleration_limits: [1.3, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/frequency: 20
 * /rosbot1/rosbot_ekf/imu0: imu
 * /rosbot1/rosbot_ekf/imu0_config: [False, False, Fa...
 * /rosbot1/rosbot_ekf/imu0_differential: True
 * /rosbot1/rosbot_ekf/imu0_linear_acceleration_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/imu0_nodelay: False
 * /rosbot1/rosbot_ekf/imu0_pose_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/imu0_queue_size: 4
 * /rosbot1/rosbot_ekf/imu0_relative: True
 * /rosbot1/rosbot_ekf/imu0_remove_gravitational_acceleration: True
 * /rosbot1/rosbot_ekf/imu0_twist_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/initial_estimate_covariance: ['1e-9', 0, 0, 0,...
 * /rosbot1/rosbot_ekf/map_frame: map
 * /rosbot1/rosbot_ekf/odom0: odom/wheel
 * /rosbot1/rosbot_ekf/odom0_config: [True, True, True...
 * /rosbot1/rosbot_ekf/odom0_differential: False
 * /rosbot1/rosbot_ekf/odom0_nodelay: False
 * /rosbot1/rosbot_ekf/odom0_queue_size: 6
 * /rosbot1/rosbot_ekf/odom0_relative: True
 * /rosbot1/rosbot_ekf/odom_frame: rosbot1/odom
 * /rosbot1/rosbot_ekf/print_diagnostics: True
 * /rosbot1/rosbot_ekf/process_noise_covariance: [0.05, 0, 0, 0, 0...
 * /rosbot1/rosbot_ekf/publish_acceleration: False
 * /rosbot1/rosbot_ekf/publish_tf: True
 * /rosbot1/rosbot_ekf/sensor_timeout: 0.2
 * /rosbot1/rosbot_ekf/stamped_control: False
 * /rosbot1/rosbot_ekf/transform_time_offset: 0.0
 * /rosbot1/rosbot_ekf/transform_timeout: 0.1
 * /rosbot1/rosbot_ekf/two_d_mode: False
 * /rosbot1/rosbot_ekf/use_control: True
 * /rosbot1/rosbot_ekf/world_frame: rosbot1/odom
 * /rosbot1/rplidar/angle_compensate: True
 * /rosbot1/rplidar/frame_id: rosbot1/laser
 * /rosbot1/rplidar/inverted: False
 * /rosbot1/rplidar/scan_mode: Sensitivity
 * /rosbot1/rplidar/serial_baudrate: 256000
 * /rosbot1/rplidar/serial_port: /dev/ttyUSB0
 * /rosbot1/rplidar/tf_prefix: rosbot1
 * /rosbot1/serial_node/baud: 525000
 * /rosbot1/serial_node/port: /dev/ttyS4
 * /rosdistro: melodic
 * /rosversion: 1.14.10

NODES
  /rosbot1/
    amcl (amcl/amcl)
    imu_publisher (tf/static_transform_publisher)
    laser_broadcaster (tf/static_transform_publisher)
    move_base_rosbot (move_base/move_base)
    msgs_conversion (rosbot_ekf/msgs_conversion)
    rosbot_ekf (robot_localization/ekf_localization_node)
    rplidar (rplidar_ros/rplidarNode)
    serial_node (rosserial_python/serial_node.py)

ROS_MASTER_URI=http://192.168.124.39:11311

process[rosbot1/rplidar-1]: started with pid [10879]
process[rosbot1/serial_node-2]: started with pid [10882]
process[rosbot1/msgs_conversion-3]: started with pid [10883]
process[rosbot1/rosbot_ekf-4]: started with pid [10888]
process[rosbot1/imu_publisher-5]: started with pid [10900]
[ INFO] [1650255754.809868973]: RPLIDAR running on ROS package rplidar_ros. SDK Version:1.12.0
process[rosbot1/laser_broadcaster-6]: started with pid [10908]
process[rosbot1/amcl-7]: started with pid [10915]
process[rosbot1/move_base_rosbot-8]: started with pid [10926]
RPLIDAR S/N: AFED9A87C5E392D2A5E492F83F38316C
[ INFO] [1650255755.348432207]: Firmware Ver: 1.27
[ INFO] [1650255755.348571525]: Hardware Rev: 6
[ INFO] [1650255755.349932589]: RPLidar health status : 0
[ WARN] [1650255755.618295037]: Both imu0_differential and imu0_relative were set to true. Using differential mode.
[ WARN] [1650255755.819247572]: ignoring NAN in initial pose Yaw
[ INFO] [1650255755.988264048]: current scan mode: Sensitivity, max_distance: 25.0 m, Point number: 15.9K , angle_compensate: 4
[ INFO] [1650255756.100860757]: Subscribed to map topic.
[INFO] [1650255756.496538]: ROS Serial Python Node
[INFO] [1650255756.546231]: Connecting to /dev/ttyS4 at 525000 baud
[ INFO] [1650255756.831424295]: Received a 928 X 1088 map @ 0.050 m/pix

[ WARN] [1650255756.914755615]: ignoring NAN in initial pose Yaw
[ INFO] [1650255756.943944545]: Initializing likelihood field model; this can take some time on large maps...
[ INFO] [1650255757.274465039]: Done initializing likelihood field model.
[INFO] [1650255758.669757]: Requesting topics...
[INFO] [1650255758.748144]: Note: publish buffer size is 512 bytes
[INFO] [1650255758.765827]: Setup service server on config [rosbot_ekf/Configuration]
[INFO] [1650255759.135813]: Setup publisher on battery [sensor_msgs/BatteryState]
[INFO] [1650255759.152471]: Setup publisher on pose [geometry_msgs/PoseStamped]
[INFO] [1650255759.175869]: Setup publisher on velocity [geometry_msgs/Twist]
[INFO] [1650255759.192930]: Setup publisher on range/fr [sensor_msgs/Range]
[INFO] [1650255759.214848]: Setup publisher on range/fl [sensor_msgs/Range]
[INFO] [1650255759.239031]: Setup publisher on range/rr [sensor_msgs/Range]
[INFO] [1650255759.257957]: Setup publisher on range/rl [sensor_msgs/Range]
[INFO] [1650255759.277333]: Setup publisher on joint_states [sensor_msgs/JointState]
[INFO] [1650255759.298208]: Setup publisher on imu [sensor_msgs/Imu]
[INFO] [1650255759.316790]: Setup publisher on buttons [std_msgs/UInt8]
[INFO] [1650255759.333055]: Note: subscribe buffer size is 512 bytes
[INFO] [1650255759.360875]: Setup subscriber on cmd_vel [geometry_msgs/Twist]
[INFO] [1650255759.394771]: Setup subscriber on cmd_ser [std_msgs/UInt32]
[INFO] [1650255759.412748]:

 ______  _____  _____  _             _           __
 | ___ \|  _  |/  ___|| |           | |         / _|
 | |_/ /| | | |\ `--. | |__    ___  | |_       | |_ __      __
 |    / | | | | `--. \| '_ \  / _ \ | __|      |  _|\ \ /\ / /
 | |\ \ \ \_/ //\__/ /| |_) || (_) || |_       | |   \ V  V /
 \_| \_| \___/ \____/ |_.__/  \___/  \__|      |_|    \_/\_/

 Firmware version: 0.15.0


[INFO] [1650255759.426611]: Detected sensor: MPU9250

[ WARN] [1650255759.606458809]: Could not obtain transform from odom to rosbot1/odom. Error was "rosbot1/odom" passed to lookupTransform argument target_frame does not exist.

[ WARN] [1650255759.909699457]: Failed to meet update rate! Took 0.43497811900000005192
[ WARN] [1650255760.866639925]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100478 timeout was 0.1.
[ WARN] [1650255761.319715855]: Failed to meet update rate! Took 1.7950355270000000196
[ WARN] [1650255761.620788644]: Could not obtain transform from odom to rosbot1/odom. Error was "rosbot1/odom" passed to lookupTransform argument target_frame does not exist.

[ WARN] [1650255762.731702447]: Failed to meet update rate! Took 2.8215937489999998178
[ WARN] [1650255763.638687238]: Could not obtain transform from odom to rosbot1/odom. Error was "rosbot1/odom" passed to lookupTransform argument target_frame does not exist.

[ WARN] [1650255764.141879649]: Failed to meet update rate! Took 2.8218772969999998956
[ WARN] [1650255765.552532613]: Failed to meet update rate! Took 2.8204987710000000156
[ WARN] [1650255765.656814882]: Could not obtain transform from imu_link to rosbot1/base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1650255766.086621613]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100278 timeout was 0.1.
[ WARN] [1650255766.968142860]: Failed to meet update rate! Took 2.8255107139999999788
[ WARN] [1650255767.673467580]: Could not obtain transform from imu_link to rosbot1/base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1650255768.382409630]: Failed to meet update rate! Took 2.8289551409999997844
[ WARN] [1650255769.692750812]: Could not obtain transform from odom to rosbot1/odom. Error was "rosbot1/odom" passed to lookupTransform argument target_frame does not exist.

[ WARN] [1650255769.794436571]: Failed to meet update rate! Took 2.8259684900000001662
[ WARN] [1650255771.116364279]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.100621 timeout was 0.1.
[ WARN] [1650255771.207169673]: Failed to meet update rate! Took 2.8243827750000001231
[ WARN] [1650255771.711851966]: Could not obtain transform from imu_link to rosbot1/base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1650255771.829168697]: No laser scan received (and thus no pose updates have been published) for 1650255771.828678 seconds.  Verify that data is being published on the /rosbot1/scan topic.
[ WARN] [1650255772.620389712]: Failed to meet update rate! Took 2.8256591189999999969
[ WARN] [1650255773.727930259]: Could not obtain transform from imu_link to rosbot1/base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1650255774.030590288]: Failed to meet update rate! Took 2.8230959690000001494
^C[rosbot1/amcl-7] killing on exit
[rosbot1/move_base_rosbot-8] killing on exit
[rosbot1/laser_broadcaster-6] killing on exit
[rosbot1/rosbot_ekf-4] killing on exit
[rosbot1/msgs_conversion-3] killing on exit
[rosbot1/imu_publisher-5] killing on exit
[rosbot1/serial_node-2] killing on exit
[rosbot1/rplidar-1] killing on exit
[INFO] [1650255775.177396]: Send tx stop request
shutting down processing monitor...
... shutting down processing monitor complete
done

And I can not have map and rosbot1/odom correctly appeared in the TF tree, Here are my TF tree and all topics,

I did some checks about rosbot/odom, and found,

  • no response to rostopic echo -n1 /rosbot1/odom or rostopic echo -n1 /odom
  • only rosbot1/base_link, rosbot1/laser and rosbot1/imu_link appeared in TF tree, here is the resutls after rosrun tf tf_echo rosbot1/odom rosbot1/base_link:

I tried to add <param name="tf_prefix" value="rosbot1" /> or change odom to rosbot1/odom like this, but all failed.

Could you give me more help! I will be so appreciated if you can help me with these issues! Thanks in advance!

BRs,
Si

Hi, Pkowalsk,

With reference to Odometry/Rosbot_ekf not working under namespace, in my launch script start_namesapce.launch, I added tf_prefix for message_conversion.launch in line 42, and removed absolute paths of odom from robot_localization in 49, 50 and 53. It looks like:

Here are the topic list, msg data of /rosbot1/odom, /rosbot1/imu, and the TF tree after launch launch_rosbot_with_name.launch,

I still got repeated warnings like:

[ WARN] [1650773660.660316260]: Could not obtain transform from imu_link to rosbot1/base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

[ WARN] [1650773660.964193215]: Failed to meet update rate! Took 0.41670220000000002258
[ WARN] [1650773661.773607929]: Failed to meet update rate! Took 1.1761404740000001024
[ WARN] [1650773661.967833834]: Timed out waiting for transform from rosbot1/base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.101034 timeout was 0.1.

In the TF tree, frame id map, and rosbot1/odom still appear correctly! I am wondering if it is right to build the correct TF tree by changing frame id imu_link to rosbot1/imu_link, and changing frame id odom to rosbot1/odom. If it is, could you please guide me hwo to do it?

Thanks in advance!

BRs,
Si

Hi Si,
A major problem is launching a message_conversion.launch. Your argument is passed to launch, but not to the msgs_conversion node. You can run it by changing lines 41-43 to:

<node pkg="rosbot_ekf" type="msgs_conversion" name="msgs_conversion" respawn="true">
  <param name="tf_prefix" type="string" value="$(arg robot_namespace)" />
</node>

This will make the frame_id contained in the odom message become rosbot1/odom (instead odom), therefore you should make further corrections in 46-59

<node pkg="robot_localization" type="ekf_localization_node" name="rosbot_ekf" clear_params="true">
  <rosparam command="load" file="$(find rosbot_ekf)/params/ekf_params.yaml" />
  <param name="base_link_frame" value="$(arg robot_namespace)/base_link"/>
  <param name="odom_frame" value="$(arg robot_namespace)/odom"/>
  <param name="world_frame" value="$(arg robot_namespace)/odom"/>

  <!--  Placeholder for output topic remapping -->
  <remap from="odometry/filtered" to="odom"/>
  <!-- <remap from="accel/filtered" to=""/> -->
</node>

<node pkg="tf" type="static_transform_publisher" name="imu_publisher" args="0 0 0.02 0 0 0 $(arg robot_namespace)/base_link imu_link 100" />
<node pkg="tf" type="static_transform_publisher" name="laser_broadcaster" args="0 0 0 3.14 0 0 $(arg robot_namespace)/base_link $(arg robot_namespace)/laser 100" />

I changed $(arg robot_namespace)/imu_link to imu_link in line 56. Unfortunately, there is no out-of-the-box tool that allows you to change frame_id in /rosbot1/imu topic to one that includes namespace. I think this solution should work, but if not, you can extend the functionality of the msgs_conversion node from rosbot_ekf package by adding support for messages from /imu topic (exactly the same as it is with odom msgs).

Results:

I hope this solution suits you, but please, let me know about it. If you have any questions/troubles, do not hesitate to ask.

Best regards,
Paweł

Hi, Pkowalsk,

Thanks so much for your help and guidance!

I finally see the “old” TF tree again, here are part of the logs after launch and the TF tree.

  • part of logs after launch
 ______  _____  _____  _             _           __
 | ___ \|  _  |/  ___|| |           | |         / _|
 | |_/ /| | | |\ `--. | |__    ___  | |_       | |_ __      __
 |    / | | | | `--. \| '_ \  / _ \ | __|      |  _|\ \ /\ / /
 | |\ \ \ \_/ //\__/ /| |_) || (_) || |_       | |   \ V  V /
 \_| \_| \___/ \____/ |_.__/  \___/  \__|      |_|    \_/\_/

 Firmware version: 0.15.0


[INFO] [1650961523.155433]: Detected sensor: MPU9250

[ WARN] [1650961523.371011568]: global_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[ INFO] [1650961523.388766863]: global_costmap: Using plugin "static_layer"
[ INFO] [1650961523.470220946]: Requesting the map...
[ INFO] [1650961523.894829140]: Resizing static layer to 928 X 1088 at 0.050000 m/pix
[ INFO] [1650961523.991632549]: Received a 928 X 1088 map at 0.050000 m/pix
[ INFO] [1650961524.015488314]: global_costmap: Using plugin "obstacle_layer"
[ INFO] [1650961524.079210403]:     Subscribed to Topics: laser_scan_sensor
[ INFO] [1650961524.243632794]: global_costmap: Using plugin "inflation_layer"
[ WARN] [1650961524.820593817]: local_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[ INFO] [1650961524.834202206]: local_costmap: Using plugin "static_layer"
[ INFO] [1650961524.913950091]: Requesting the map...
[ INFO] [1650961524.947805780]: Resizing static layer to 928 X 1088 at 0.050000 m/pix
[ INFO] [1650961525.036734449]: Received a 928 X 1088 map at 0.050000 m/pix
[ INFO] [1650961525.086324147]: local_costmap: Using plugin "obstacle_layer"
[ INFO] [1650961525.127546212]:     Subscribed to Topics: laser_scan_sensor
[ INFO] [1650961525.298782345]: local_costmap: Using plugin "inflation_layer"
[ INFO] [1650961525.679597302]: Created local_planner base_local_planner/TrajectoryPlannerROS
[ INFO] [1650961525.779851238]: Sim period is set to 0.05
[ WARN] [1650961531.489246062]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 6.8925 seconds
[ INFO] [1650961531.647772919]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1650961531.713864862]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1650961532.021930820]: odom received!
[ WARN] [1650961537.710963948]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 6.2217 seconds
[ WARN] [1650961544.427809887]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 6.7169 seconds
[ WARN] [1650961550.811442606]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 6.3836 seconds
[ WARN] [1650961552.520012877]: Costmap2DROS transform timeout. Current time: 1650961552.5198, global_pose stamp: 1650961551.6931, tolerance: 0.8000
[ WARN] [1650961552.520198394]: Could not get robot pose, cancelling reconfiguration

I am wondering if I can add namespace rosbot1 into the frame_id of /imu message by modifying msgs_conversion.cpp as post Odometry/Rosbot_ekf not working under namespace suggested to convert /imu message,

  • adding function mpuCallback to convert the frame id
  • adding new publisher for imu

if yes, could you tell me where I can include file rosbot_ekf/Imu.h and sensor_msgs/Imu.h to remake rosbot_ekf package?

Thanks again!

BRs,
Si

Hi,

It is enough to add mpuCallback function (similar to poseCallback) and /imu subsricber to the msgs_conversion.cpp file.

Best regards,
Paweł

Hi, Pkowalsk,

Thanks a lot for your help! With you guidance, I succesffly rebult rosbot_ekf package with modified msgs_conversion.cpp.

But after I launched my scripts (without any change in my launch script start_namesapce.launch), the TF tree is still like the one in previous, the frame_id of /imu message is still imu_link, not rosbot1/imu_link.

I tried to change imu_link to $(arg robot_namespace)/imu_link in line 56 of my launch script start_namesapce.launch. After launch, the frameid of ‘imu_link’ changed to rosbot1/imu_link, but I also recived warning [ WARN] [1652329945.327612312]: Could not obtain transform from imu_link to rosbot1/base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

Could you please tell me why and how to fix it? Thanks in advance!

BTW, I am not sure if this way works for multiple rosbot robots running at the same time, like “rosbot1”, “rosbot2”, because they all subscribed same topics “pose” and “mpu9250” in the msgs_conversion.cpp!

Here is the modified msgs_conversion.cpp:

#include "ros/ros.h"
#include "geometry_msgs/PoseStamped.h"
#include "nav_msgs/Odometry.h"
#include <string>
#include "rosbot_ekf/Imu.h"
#include "sensor_msgs/Imu.h"

#define ODOM_COV 0.005
#define MAIN_LOOP_RATE 20
#define IMU_ORIENTATION_COV 0.05
#define IMU_ANG_VEL_COV 0.1
#define IMU_LIN_ACCEL_COV 0.5
#define PI 3.1415
#define G_ACCEL 9.8066

ros::Publisher *odom_pub_ptr;
ros::Publisher *imu_pub_ptr;
std::string tf_prefix_;
bool has_prefix;

void poseCallback(const geometry_msgs::PoseStamped &pose_msg)
{
  nav_msgs::Odometry odom_msg;

  odom_msg.pose.pose.orientation.x = pose_msg.pose.orientation.x;
  odom_msg.pose.pose.orientation.y = pose_msg.pose.orientation.y;
  odom_msg.pose.pose.orientation.z = pose_msg.pose.orientation.z;
  odom_msg.pose.pose.orientation.w = pose_msg.pose.orientation.w;

  odom_msg.pose.pose.position.x = pose_msg.pose.position.x;
  odom_msg.pose.pose.position.y = pose_msg.pose.position.y;
  odom_msg.pose.pose.position.z = pose_msg.pose.position.z;

  odom_msg.pose.covariance[0] = ODOM_COV;
  odom_msg.pose.covariance[7] = ODOM_COV;
  odom_msg.pose.covariance[14] = ODOM_COV;
  odom_msg.pose.covariance[21] = ODOM_COV;
  odom_msg.pose.covariance[28] = ODOM_COV;
  odom_msg.pose.covariance[35] = ODOM_COV;

  odom_msg.header = pose_msg.header;
  if (has_prefix)
  {
    odom_msg.header.frame_id = tf_prefix_ + "/odom";
  }
  else
  {
    odom_msg.header.frame_id = "odom";
  }
  odom_pub_ptr->publish(odom_msg);
}


void mpuCallback(const rosbot_ekf::Imu &mpu_msg)
{
  sensor_msgs::Imu imu_msg;

  imu_msg.header = mpu_msg.header;
  if(has_prefix){
    imu_msg.header.frame_id = tf_prefix_ + "/imu_link";
  }
  else{
    imu_msg.header.frame_id = "imu_link";
  }

  imu_msg.orientation.x = mpu_msg.orientation.x;
  imu_msg.orientation.y = mpu_msg.orientation.y;
  imu_msg.orientation.z = mpu_msg.orientation.z;
  imu_msg.orientation.w = mpu_msg.orientation.w;

  imu_msg.angular_velocity.x = mpu_msg.angular_velocity[0] * PI / 180;
  imu_msg.angular_velocity.y = mpu_msg.angular_velocity[1] * PI / 180;
  imu_msg.angular_velocity.z = mpu_msg.angular_velocity[2] * PI / 180;

  imu_msg.linear_acceleration.x = mpu_msg.linear_acceleration[0] * G_ACCEL;
  imu_msg.linear_acceleration.y = mpu_msg.linear_acceleration[1] * G_ACCEL;
  imu_msg.linear_acceleration.z = mpu_msg.linear_acceleration[2] * G_ACCEL;

  imu_msg.orientation_covariance[0] = IMU_ORIENTATION_COV;
  imu_msg.orientation_covariance[4] = IMU_ORIENTATION_COV;
  imu_msg.orientation_covariance[8] = IMU_ORIENTATION_COV;

  imu_msg.angular_velocity_covariance[0] = IMU_ANG_VEL_COV;
  imu_msg.angular_velocity_covariance[4] = IMU_ANG_VEL_COV;
  imu_msg.angular_velocity_covariance[8] = IMU_ANG_VEL_COV;

  imu_msg.linear_acceleration_covariance[0] = IMU_LIN_ACCEL_COV;
  imu_msg.linear_acceleration_covariance[4] = IMU_LIN_ACCEL_COV;
  imu_msg.linear_acceleration_covariance[8] = IMU_LIN_ACCEL_COV;



  imu_pub_ptr->publish(imu_msg);

}


int main(int argc, char **argv)
{

  ros::init(argc, argv, "msgs_conversion");

  ros::NodeHandle n;

  has_prefix = ros::param::get("~tf_prefix", tf_prefix_);

  ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom/wheel", 1);
  odom_pub_ptr = &odom_pub;
  ros::Publisher imu_pub = n.advertise<sensor_msgs::Imu>("imu", 1);
  imu_pub_ptr = &imu_pub;

  ros::Subscriber pose_sub = n.subscribe("pose", 1000, poseCallback);
  ros::Subscriber mpu_sub = n.subscribe("mpu9250", 1000, mpuCallback);

  ros::Rate loop_rate(MAIN_LOOP_RATE);

  while (ros::ok())
  {
    ros::spinOnce();
    loop_rate.sleep();
  }

  return 0;
}

Hi,
I’m afraid that your callback function can never be called. It’s becouse mpu9250 data is published on the imu topic (since a few months). Also check if you should subscribe to a topic whose name contains namespace rosbot1. After solving this problem, make sure the frame_id in this topic is rosbot1/imu

Please, let me know about it. If you have any questions/troubles, do not hesitate to ask.

Best regards,
Paweł

Hi, Pkowalsk,

Thanks a lot for you help!

I tried to change the subscribed topic mpu9250 to imu, after remake and launch, I got the following errors, and the frameid of topic /rosbot/imu was still imu_link

[ERROR] [1652755264.857741940]: md5sum mismatch making local subscription to topic /rosbot1/imu.
[ERROR] [1652755264.870051328]: Subscriber expects type rosbot_ekf/Imu, md5sum 3d83bdcabfe2927ed38c36f102a9f646
[ERROR] [1652755264.870639655]: Publisher provides type sensor_msgs/Imu, md5sum 6a62c6daae103f4ff57a132d6f95cec2
[ WARN] [1652755264.871127061]: couldn't register subscriber on topic [/rosbot1/imu]

I also tried to add namessapce rosbot1 before the subscribed topics pose and imu in msgs_conversion.cpp, errors kept the same.

Could you please help again to check it? Thanks in advance!

BRs,
Si

Hi, Pkowalsk,

After modified the msgs_conversion.cpp, I successfully added frame_id rosbot1 into topic /rosbot1/imu. But I still have some problems in launching the robot and building the TF tree.

trial 1

If I keep the static transform from base_link to imu_link like:

<node pkg="tf" type="static_transform_publisher" name="imu_publisher" args="0 0 0.02 0 0 0 $(arg robot_namespace)/base_link imu_link 100" />

I will get warning after launch launch_rosbot_with_name.launch and start_namesapce.launch

  • launch warning
[ WARN] [1653468352.296138188]: Could not obtain transform from rosbot1/imu_link to rosbot1/base_link. Error was "rosbot1/imu_link" passed to lookupTransform argument source_frame does not exist.

trial 2

If I added $(arg robot_namespace) before imu_link in the static transform from base_link to imu_link like:

<node pkg="tf" type="static_transform_publisher" name="imu_publisher" args="0 0 0.02 0 0 0 $(arg robot_namespace)/base_link $(arg robot_namespace)/imu_link 100" />

I will get different warning after launch:

  • launch warning
[ WARN] [1653468827.681125155]: Could not obtain transform from imu_link to rosbot1/base_link. Error was "imu_link" passed to lookupTransform argument source_frame does not exist.

Here is the modified msgs_conversion.cpp:

#include "ros/ros.h"
#include "geometry_msgs/PoseStamped.h"
#include "nav_msgs/Odometry.h"
#include <string>
#include "rosbot_ekf/Imu.h"
#include "sensor_msgs/Imu.h"

#define ODOM_COV 0.005
#define MAIN_LOOP_RATE 20

ros::Publisher *odom_pub_ptr;
ros::Publisher *imu_pub_ptr;
std::string tf_prefix_;
bool has_prefix;

void poseCallback(const geometry_msgs::PoseStamped &pose_msg)
{
  nav_msgs::Odometry odom_msg;

  odom_msg.pose.pose.orientation.x = pose_msg.pose.orientation.x;
  odom_msg.pose.pose.orientation.y = pose_msg.pose.orientation.y;
  odom_msg.pose.pose.orientation.z = pose_msg.pose.orientation.z;
  odom_msg.pose.pose.orientation.w = pose_msg.pose.orientation.w;

  odom_msg.pose.pose.position.x = pose_msg.pose.position.x;
  odom_msg.pose.pose.position.y = pose_msg.pose.position.y;
  odom_msg.pose.pose.position.z = pose_msg.pose.position.z;

  odom_msg.pose.covariance[0] = ODOM_COV;
  odom_msg.pose.covariance[7] = ODOM_COV;
  odom_msg.pose.covariance[14] = ODOM_COV;
  odom_msg.pose.covariance[21] = ODOM_COV;
  odom_msg.pose.covariance[28] = ODOM_COV;
  odom_msg.pose.covariance[35] = ODOM_COV;

  odom_msg.header = pose_msg.header;
  if (has_prefix)
  {
    odom_msg.header.frame_id = tf_prefix_ + "/odom";
  }
  else
  {
    odom_msg.header.frame_id = "odom";
  }
  odom_pub_ptr->publish(odom_msg);
}

int main(int argc, char **argv)
{

  ros::init(argc, argv, "msgs_conversion");

  ros::NodeHandle n;

  has_prefix = ros::param::get("~tf_prefix", tf_prefix_);

  ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom/wheel", 1);
  odom_pub_ptr = &odom_pub;
  ros::Publisher imu_pub = n.advertise<sensor_msgs::Imu>("imu", 1);
  imu_pub_ptr = &imu_pub;

  ros::Subscriber pose_sub = n.subscribe("/rosbot1/pose", 1000, poseCallback);
  ros::Subscriber mpu_sub = n.subscribe("/rosbot1/imu", 1000, imuCallback);

  ros::Rate loop_rate(MAIN_LOOP_RATE);

  while (ros::ok())
  {
    ros::spinOnce();
    loop_rate.sleep();
  }

  return 0;
}

Could you please help me to have a check? Thanks a lot in advance!

BRs,
Si

Hi,
My initial guess is that the rosbot1/imu topic contains messages with both the rosbot1/imu and imu frames. Please try to change publisher topic in your msgs_conversion node from imu to i.e. imu_conversion. Next, try to change imu topic in your launch:

<node pkg="robot_localization" type="ekf_localization_node" name="rosbot_ekf" clear_params="true">
        <rosparam command="load" file="$(find rosbot_ekf)/params/ekf_params.yaml" />
        <param name="base_link_frame" value="$(arg robot_namespace)/base_link"/>
        <param name="odom_frame" value="$(arg robot_namespace)/odom"/>
        <param name="world_frame" value="$(arg robot_namespace)/odom"/>
        <param name="imu0" value="$(arg robot_namespace)/imu_conversion"/> <!--  here -->

        <!--  Placeholder for output topic remapping -->
        <remap from="odometry/filtered" to="odom"/>
        <!-- <remap from="accel/filtered" to=""/> -->
</node>

I hope this solution suits you.

Best regards,
Paweł

Hi, Pkowalsk,

Thanks a lot for yur guidance! I successfully built the TF tree now.

New problem comes out! My robot behaves weirdly in navigation after I launch it by my launch script [launch_rosbot launch_rosbot_with_name.launch](launch_rosbot/launch_rosbot_with_name.launch at main · wdxpz/launch_rosbot · GitHub and issue a target position.

warnings in the follwoing will keep popping out after odom received! when I launch:

[ WARN] [1654761096.540290903]: Costmap2DROS transform timeout. Current time: 1654761096.5401, global_pose stamp: 1654761094.6967, tolerance: 0.8000
[ WARN] [1654761096.540468682]: Could not get robot pose, cancelling reconfiguration

After I send target position to the robot by actionlib.SimpleActionClient and MoveBaseGoal after init it position, it will pop out errors and warnings like:

[ERROR] [1654761965.617714978]: Couldn't determine robot's pose associated with laser scan
[ WARN] [1654761965.618165939]: Failed to compute odom pose, skipping scan (Lookup would require extrapolation into the future.  Requested time 1654761955.414014200 but the latest data is at time 1654761954.317594114, when looking up transform from frame [rosbot1/base_link] to frame [rosbot1/odom])

I am lost now for the params for amcl and configuratons for move_base were OK when I do the navigation before I upgraded from Kinetic to Melodic. I only removed / in the params odom_frame_id and base_frame_id of amcl module in start_namesapce.launch:

 <node pkg="amcl" type="amcl" name="amcl" output="screen">
            <remap from="map" to="/map"/>
            <remap from="static_map" to="/static_map"/>
            <remap from="scan" to="scan"/>
            <remap from="initialpose" to="initialpose"/>
            <remap from="amcl_pose" to="amcl_pose"/>
            <remap from="particlecloud" to="particlecloud"/>
            <param name="odom_frame_id" value="$(arg robot_namespace)/odom"/>  <!--  here -->
            <param name="base_frame_id" value="$(arg robot_namespace)/base_link"/> <!--  here -->
            <param name="odom_model_type" value="diff-corrected"/>
            <param name="update_min_d" value="0.1"/>
            <param name="update_min_a" value="1.0"/>
            <param name="global_frame_id" value="map" />
            <param name="use_map_topic" value="true" />
            <param name="min_particles" value="1000"/>
            <param name="max_particles" value="5000"/>
            <param name="initial_pose_x"            value="$(arg initial_pose_x)"/>
            <param name="initial_pose_y"            value="$(arg initial_pose_y)"/>
            <param name="initial_pose_z"            value="$(arg initial_pose_z)"/>
</node>

I’d like to seek your help again! Could you please chekc my code and configuration in here again? Thanks in advance!

BRs,
Si

Hi,

I’m afraid your question is about third-party developer solutions, which is not directly related to the problem of running ROSbot. You can ask about it at https://answers.ros.org/questions, for example.

Best regards,
Paweł

Hi, Pkowalsk,

I doubt that there are some problems with my lidar.

I found that the lidar will fail to start to rotate sometimes after I launch with my own launch file. In another trial, the lidar started to rotate, but I got error:

No laser scan received (and thus no pose updates have been published) for 1655194664.028107 seconds.  Verify that data is being published on the /rosbot1/scan topic

then I went to check this topic, but no reponse to my rostipic echo /rosbot1/scan even though this topic is there.

So I did another trial, I just launched the lidar by:

roslaunch rplidar_ros rplidar_a3.launch

the lidar behaved like before, sometimes it failed to start with error:
[ERROR] [1655196344.166891901]: Error, operation time out. RESULT_OPERATION_TIMEOUT!

sometimes it started with error [ERROR] [1655196152.084046637]: Can not start scan: 80008000!, here is the full logs:

Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://192.168.28.135:33601/

SUMMARY
========

PARAMETERS
 * /rosdistro: melodic
 * /rosversion: 1.14.10
 * /rplidarNode/angle_compensate: True
 * /rplidarNode/frame_id: laser
 * /rplidarNode/inverted: False
 * /rplidarNode/scan_mode: Sensitivity
 * /rplidarNode/serial_baudrate: 256000
 * /rplidarNode/serial_port: /dev/ttyUSB0

NODES
  /
    rplidarNode (rplidar_ros/rplidarNode)

ROS_MASTER_URI=http://192.168.28.83:11311

process[rplidarNode-1]: started with pid [13212]
[ INFO] [1655196149.035925460]: RPLIDAR running on ROS package rplidar_ros. SDK Version:1.12.0
RPLIDAR S/N: AFED9A87C5E392D2A5E492F83F38316C
[ INFO] [1655196149.552952133]: Firmware Ver: 1.27
[ INFO] [1655196149.553066176]: Hardware Rev: 6
[ INFO] [1655196149.554194363]: RPLidar health status : 0
[ERROR] [1655196152.084046637]: Can not start scan: 80008000!

I tried to echo topic /scan when it started, but still no reponse!

Untitled

Could you give me some hints? Thanks in advance!

BRs,
Si

Hi,

this LIDAR topic will be continued in the following post:

Best regards,
Paweł

Hi, Pkowalsk,

Thanks a lot for your help! I finally managed to get the rplidar working and I can get odom received! after launch my scripts with!

Here are the full logs after the launch:

... logging to /home/husarion/.ros/log/39fbb41a-fe96-11ec-b35d-10c37b50f238/roslaunch-husarion-22767.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://192.168.28.174:40929/

SUMMARY
========

CLEAR PARAMETERS
 * /rosbot1/rosbot_ekf/

PARAMETERS
 * /rosbot1/amcl/base_frame_id: rosbot1/base_link
 * /rosbot1/amcl/global_frame_id: map
 * /rosbot1/amcl/initial_pose_x: 0.0
 * /rosbot1/amcl/initial_pose_y: 0.0
 * /rosbot1/amcl/initial_pose_z: 0.0
 * /rosbot1/amcl/max_particles: 5000
 * /rosbot1/amcl/min_particles: 1000
 * /rosbot1/amcl/odom_frame_id: rosbot1/odom
 * /rosbot1/amcl/odom_model_type: diff-corrected
 * /rosbot1/amcl/update_min_a: 1.0
 * /rosbot1/amcl/update_min_d: 0.1
 * /rosbot1/amcl/use_map_topic: True
 * /rosbot1/move_base_rosbot/DWAPlannerROS/global_frame_id: rosbot1/odom
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_Y: 1.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_theta: 5.0
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/acc_lim_x: 1.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/holonomic_robot: False
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/max_vel_theta: 2.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/max_vel_x: 0.1
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/meter_scoring: True
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_in_place_vel_theta: 0.25
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_vel_theta: -2.5
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/min_vel_x: 0.01
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/xy_goal_tolerance: 0.05
 * /rosbot1/move_base_rosbot/TrajectoryPlannerROS/yaw_goal_tolerance: 0.05
 * /rosbot1/move_base_rosbot/global_costmap/always_send_full_costmap: True
 * /rosbot1/move_base_rosbot/global_costmap/footprint: [[0.12, 0.14], [0...
 * /rosbot1/move_base_rosbot/global_costmap/global_frame: map
 * /rosbot1/move_base_rosbot/global_costmap/height: 25
 * /rosbot1/move_base_rosbot/global_costmap/inflation_radius: 2.5
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/clearing: True
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/data_type: LaserScan
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/marking: True
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/sensor_frame: rosbot1/laser
 * /rosbot1/move_base_rosbot/global_costmap/laser_scan_sensor/topic: /rosbot1/scan
 * /rosbot1/move_base_rosbot/global_costmap/map_topic: map
 * /rosbot1/move_base_rosbot/global_costmap/observation_sources: laser_scan_sensor
 * /rosbot1/move_base_rosbot/global_costmap/obstacle_range: 6.0
 * /rosbot1/move_base_rosbot/global_costmap/publish_frequency: 0.5
 * /rosbot1/move_base_rosbot/global_costmap/raytrace_range: 8.5
 * /rosbot1/move_base_rosbot/global_costmap/resolution: 0.01
 * /rosbot1/move_base_rosbot/global_costmap/robot_base_frame: rosbot1/base_link
 * /rosbot1/move_base_rosbot/global_costmap/rolling_window: True
 * /rosbot1/move_base_rosbot/global_costmap/static_map: True
 * /rosbot1/move_base_rosbot/global_costmap/subscribe_to_updates: True
 * /rosbot1/move_base_rosbot/global_costmap/transform_tolerance: 0.8
 * /rosbot1/move_base_rosbot/global_costmap/update_frequency: 0.5
 * /rosbot1/move_base_rosbot/global_costmap/width: 50
 * /rosbot1/move_base_rosbot/local_costmap/always_send_full_costmap: True
 * /rosbot1/move_base_rosbot/local_costmap/footprint: [[0.12, 0.14], [0...
 * /rosbot1/move_base_rosbot/local_costmap/global_frame: rosbot1/odom
 * /rosbot1/move_base_rosbot/local_costmap/height: 3
 * /rosbot1/move_base_rosbot/local_costmap/inflation_radius: 1.0
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/clearing: True
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/data_type: LaserScan
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/marking: True
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/sensor_frame: rosbot1/laser
 * /rosbot1/move_base_rosbot/local_costmap/laser_scan_sensor/topic: /rosbot1/scan
 * /rosbot1/move_base_rosbot/local_costmap/map_topic: map
 * /rosbot1/move_base_rosbot/local_costmap/observation_sources: laser_scan_sensor
 * /rosbot1/move_base_rosbot/local_costmap/obstacle_range: 6.0
 * /rosbot1/move_base_rosbot/local_costmap/origin_x: -1.5
 * /rosbot1/move_base_rosbot/local_costmap/origin_y: -1.5
 * /rosbot1/move_base_rosbot/local_costmap/publish_frequency: 5
 * /rosbot1/move_base_rosbot/local_costmap/raytrace_range: 8.5
 * /rosbot1/move_base_rosbot/local_costmap/resolution: 0.01
 * /rosbot1/move_base_rosbot/local_costmap/robot_base_frame: rosbot1/base_link
 * /rosbot1/move_base_rosbot/local_costmap/rolling_window: True
 * /rosbot1/move_base_rosbot/local_costmap/static_map: True
 * /rosbot1/move_base_rosbot/local_costmap/subscribe_to_updates: True
 * /rosbot1/move_base_rosbot/local_costmap/transform_tolerance: 0.25
 * /rosbot1/move_base_rosbot/local_costmap/update_frequency: 5
 * /rosbot1/move_base_rosbot/local_costmap/width: 3
 * /rosbot1/msgs_conversion/tf_prefix: rosbot1
 * /rosbot1/rosbot_ekf/acceleration_gains: [0.8, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/acceleration_limits: [1.3, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/base_link_frame: rosbot1/base_link
 * /rosbot1/rosbot_ekf/control_config: [True, False, Fal...
 * /rosbot1/rosbot_ekf/control_timeout: 0.2
 * /rosbot1/rosbot_ekf/debug: False
 * /rosbot1/rosbot_ekf/debug_out_file: /path/to/debug/fi...
 * /rosbot1/rosbot_ekf/deceleration_gains: [1.0, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/deceleration_limits: [1.3, 0.0, 0.0, 0...
 * /rosbot1/rosbot_ekf/frequency: 20
 * /rosbot1/rosbot_ekf/imu0: imu_conversion
 * /rosbot1/rosbot_ekf/imu0_config: [False, False, Fa...
 * /rosbot1/rosbot_ekf/imu0_differential: True
 * /rosbot1/rosbot_ekf/imu0_linear_acceleration_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/imu0_nodelay: False
 * /rosbot1/rosbot_ekf/imu0_pose_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/imu0_queue_size: 4
 * /rosbot1/rosbot_ekf/imu0_relative: True
 * /rosbot1/rosbot_ekf/imu0_remove_gravitational_acceleration: True
 * /rosbot1/rosbot_ekf/imu0_twist_rejection_threshold: 0.8
 * /rosbot1/rosbot_ekf/initial_estimate_covariance: ['1e-9', 0, 0, 0,...
 * /rosbot1/rosbot_ekf/map_frame: map
 * /rosbot1/rosbot_ekf/odom0: odom/wheel
 * /rosbot1/rosbot_ekf/odom0_config: [True, True, True...
 * /rosbot1/rosbot_ekf/odom0_differential: False
 * /rosbot1/rosbot_ekf/odom0_nodelay: False
 * /rosbot1/rosbot_ekf/odom0_queue_size: 6
 * /rosbot1/rosbot_ekf/odom0_relative: True
 * /rosbot1/rosbot_ekf/odom_frame: rosbot1/odom
 * /rosbot1/rosbot_ekf/print_diagnostics: True
 * /rosbot1/rosbot_ekf/process_noise_covariance: [0.05, 0, 0, 0, 0...
 * /rosbot1/rosbot_ekf/publish_acceleration: False
 * /rosbot1/rosbot_ekf/publish_tf: True
 * /rosbot1/rosbot_ekf/sensor_timeout: 0.2
 * /rosbot1/rosbot_ekf/stamped_control: False
 * /rosbot1/rosbot_ekf/transform_time_offset: 0.0
 * /rosbot1/rosbot_ekf/transform_timeout: 0.1
 * /rosbot1/rosbot_ekf/two_d_mode: False
 * /rosbot1/rosbot_ekf/use_control: True
 * /rosbot1/rosbot_ekf/world_frame: rosbot1/odom
 * /rosbot1/rplidar/angle_compensate: True
 * /rosbot1/rplidar/frame_id: rosbot1/laser
 * /rosbot1/rplidar/inverted: False
 * /rosbot1/rplidar/scan_mode: Sensitivity
 * /rosbot1/rplidar/serial_baudrate: 256000
 * /rosbot1/rplidar/serial_port: /dev/ttyUSB0
 * /rosbot1/rplidar/tf_prefix: rosbot1
 * /rosbot1/serial_node/baud: 525000
 * /rosbot1/serial_node/port: /dev/ttyS4
 * /rosdistro: melodic
 * /rosversion: 1.14.10

NODES
  /rosbot1/
    amcl (amcl/amcl)
    imu_publisher (tf/static_transform_publisher)
    laser_broadcaster (tf/static_transform_publisher)
    move_base_rosbot (move_base/move_base)
    msgs_conversion (rosbot_ekf/msgs_conversion)
    rosbot_ekf (robot_localization/ekf_localization_node)
    rplidar (rplidar_ros/rplidarNode)
    serial_node (rosserial_python/serial_node.py)

ROS_MASTER_URI=http://192.168.28.103:11311

process[rosbot1/rplidar-1]: started with pid [23060]
process[rosbot1/serial_node-2]: started with pid [23062]
process[rosbot1/msgs_conversion-3]: started with pid [23064]
process[rosbot1/rosbot_ekf-4]: started with pid [23068]
process[rosbot1/imu_publisher-5]: started with pid [23073]
process[rosbot1/laser_broadcaster-6]: started with pid [23087]
process[rosbot1/amcl-7]: started with pid [23091]
[ INFO] [1657271387.567382840]: RPLIDAR running on ROS package rplidar_ros, SDK Version:2.0.0
process[rosbot1/move_base_rosbot-8]: started with pid [23098]
[ INFO] [1657271387.637011064]: RPLIDAR S/N: AFED9A87C5E392D2A5E492F83F38316C
[ INFO] [1657271387.637696471]: Firmware Ver: 1.27
[ INFO] [1657271387.638431724]: Hardware Rev: 6
[ INFO] [1657271387.690494823]: RPLidar health status : OK.
[ INFO] [1657271388.004921229]: current scan mode: Sensitivity, sample rate: 16 Khz, max_distance: 25.0 m, scan frequency:10.0 Hz,
[INFO] [1657271388.690812]: ROS Serial Python Node
[INFO] [1657271388.770375]: Connecting to /dev/ttyS4 at 525000 baud
[ WARN] [1657271388.811262228]: Both imu0_differential and imu0_relative were set to true. Using differential mode.
[ INFO] [1657271389.431185393]: Subscribed to map topic.
[INFO] [1657271390.906885]: Requesting topics...
[INFO] [1657271390.938573]: Note: publish buffer size is 512 bytes
[INFO] [1657271390.958701]: Setup service server on config [rosbot_ekf/Configuration]
[ INFO] [1657271391.238367738]: Received a 928 X 1088 map @ 0.050 m/pix

[INFO] [1657271391.261016]: Setup publisher on battery [sensor_msgs/BatteryState]
[INFO] [1657271391.293761]: Setup publisher on pose [geometry_msgs/PoseStamped]
[INFO] [1657271391.347192]: Setup publisher on velocity [geometry_msgs/Twist]
[INFO] [1657271391.376612]: Setup publisher on range/fr [sensor_msgs/Range]
[INFO] [1657271391.427542]: Setup publisher on range/fl [sensor_msgs/Range]
[ INFO] [1657271391.439463110]: Initializing likelihood field model; this can take some time on large maps...
[INFO] [1657271391.447274]: Setup publisher on range/rr [sensor_msgs/Range]
[INFO] [1657271391.469009]: Setup publisher on range/rl [sensor_msgs/Range]
[INFO] [1657271391.532056]: Setup publisher on joint_states [sensor_msgs/JointState]
[INFO] [1657271391.581518]: Setup publisher on imu [sensor_msgs/Imu]
[INFO] [1657271391.636675]: Setup publisher on buttons [std_msgs/UInt8]
[INFO] [1657271391.649049]: Note: subscribe buffer size is 512 bytes
[INFO] [1657271391.684276]: Setup subscriber on cmd_vel [geometry_msgs/Twist]
[INFO] [1657271391.744358]: Setup subscriber on cmd_ser [std_msgs/UInt32]
[INFO] [1657271391.757556]:

 ______  _____  _____  _             _           __
 | ___ \|  _  |/  ___|| |           | |         / _|
 | |_/ /| | | |\ `--. | |__    ___  | |_       | |_ __      __
 |    / | | | | `--. \| '_ \  / _ \ | __|      |  _|\ \ /\ / /
 | |\ \ \ \_/ //\__/ /| |_) || (_) || |_       | |   \ V  V /
 \_| \_| \___/ \____/ |_.__/  \___/  \__|      |_|    \_/\_/

 Firmware version: 0.15.0


[INFO] [1657271391.772810]: Detected sensor: MPU9250

[ INFO] [1657271391.814197389]: Done initializing likelihood field model.
[ WARN] [1657271391.971866007]: global_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[ INFO] [1657271392.013382515]: global_costmap: Using plugin "static_layer"
[ INFO] [1657271392.150548220]: Requesting the map...
[ INFO] [1657271392.983907816]: Resizing static layer to 928 X 1088 at 0.050000 m/pix
[ INFO] [1657271393.081107372]: Received a 928 X 1088 map at 0.050000 m/pix
[ INFO] [1657271393.111929223]: global_costmap: Using plugin "obstacle_layer"
[ INFO] [1657271393.195686859]:     Subscribed to Topics: laser_scan_sensor
[ INFO] [1657271393.522891433]: global_costmap: Using plugin "inflation_layer"
[ WARN] [1657271394.428567830]: local_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[ INFO] [1657271394.442723051]: local_costmap: Using plugin "static_layer"
[ INFO] [1657271394.603607007]: Requesting the map...
[ INFO] [1657271394.634267281]: Resizing static layer to 928 X 1088 at 0.050000 m/pix
[ INFO] [1657271394.730463862]: Received a 928 X 1088 map at 0.050000 m/pix
[ INFO] [1657271394.769755945]: local_costmap: Using plugin "obstacle_layer"
[ INFO] [1657271394.948726501]:     Subscribed to Topics: laser_scan_sensor
[ INFO] [1657271395.756573072]: local_costmap: Using plugin "inflation_layer"
[ INFO] [1657271396.879919686]: Created local_planner base_local_planner/TrajectoryPlannerROS
[ INFO] [1657271397.095695662]: Sim period is set to 0.05
[ WARN] [1657271399.888842123]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 5.7608 seconds
[ INFO] [1657271399.972024305]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1657271400.105270111]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1657271400.771953283]: odom received!
[ WARN] [1657271405.408725436]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 5.5199 seconds
[ WARN] [1657271410.566668761]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 5.1579 seconds

here is the topic list after launch:

/diagnostics
/map
/map_metadata
/rosbot1/amcl/parameter_descriptions
/rosbot1/amcl/parameter_updates
/rosbot1/amcl_pose
/rosbot1/battery
/rosbot1/buttons
/rosbot1/cmd_ser
/rosbot1/cmd_vel
/rosbot1/imu
/rosbot1/imu_conversion
/rosbot1/initialpose
/rosbot1/joint_states
/rosbot1/move_base/cancel
/rosbot1/move_base/feedback
/rosbot1/move_base/goal
/rosbot1/move_base/result
/rosbot1/move_base/status
/rosbot1/move_base_rosbot/NavfnROS/plan
/rosbot1/move_base_rosbot/TrajectoryPlannerROS/cost_cloud
/rosbot1/move_base_rosbot/TrajectoryPlannerROS/global_plan
/rosbot1/move_base_rosbot/TrajectoryPlannerROS/local_plan
/rosbot1/move_base_rosbot/TrajectoryPlannerROS/parameter_descriptions
/rosbot1/move_base_rosbot/TrajectoryPlannerROS/parameter_updates
/rosbot1/move_base_rosbot/current_goal
/rosbot1/move_base_rosbot/global_costmap/costmap
/rosbot1/move_base_rosbot/global_costmap/costmap_updates
/rosbot1/move_base_rosbot/global_costmap/footprint
/rosbot1/move_base_rosbot/global_costmap/inflation_layer/parameter_descriptions
/rosbot1/move_base_rosbot/global_costmap/inflation_layer/parameter_updates
/rosbot1/move_base_rosbot/global_costmap/obstacle_layer/parameter_descriptions
/rosbot1/move_base_rosbot/global_costmap/obstacle_layer/parameter_updates
/rosbot1/move_base_rosbot/global_costmap/parameter_descriptions
/rosbot1/move_base_rosbot/global_costmap/parameter_updates
/rosbot1/move_base_rosbot/global_costmap/static_layer/parameter_descriptions
/rosbot1/move_base_rosbot/global_costmap/static_layer/parameter_updates
/rosbot1/move_base_rosbot/local_costmap/costmap
/rosbot1/move_base_rosbot/local_costmap/costmap_updates
/rosbot1/move_base_rosbot/local_costmap/footprint
/rosbot1/move_base_rosbot/local_costmap/inflation_layer/parameter_descriptions
/rosbot1/move_base_rosbot/local_costmap/inflation_layer/parameter_updates
/rosbot1/move_base_rosbot/local_costmap/obstacle_layer/parameter_descriptions
/rosbot1/move_base_rosbot/local_costmap/obstacle_layer/parameter_updates
/rosbot1/move_base_rosbot/local_costmap/parameter_descriptions
/rosbot1/move_base_rosbot/local_costmap/parameter_updates
/rosbot1/move_base_rosbot/local_costmap/static_layer/parameter_descriptions
/rosbot1/move_base_rosbot/local_costmap/static_layer/parameter_updates
/rosbot1/move_base_rosbot/parameter_descriptions
/rosbot1/move_base_rosbot/parameter_updates
/rosbot1/move_base_simple/goal
/rosbot1/odom
/rosbot1/odom/wheel
/rosbot1/particlecloud
/rosbot1/pose
/rosbot1/range/fl
/rosbot1/range/fr
/rosbot1/range/rl
/rosbot1/range/rr
/rosbot1/scan
/rosbot1/set_pose
/rosbot1/velocity
/rosout
/rosout_agg
/tf
/tf_static

I am now trying to do the map navigation with the namespace, however I got failure after I sent target position to rosbot1/move_base by actionlib by my scripts goto_m.py

I also modified line 7 of config file costmap_common_params.yaml

here are the warning and error logs after send target positions to the robot:

[ INFO] [1657271532.004975381]: Setting pose (1657271532.004894): 0.000 0.000 -0.000
[ INFO] [1657271532.957326799]: Setting pose (1657271532.957246): 0.000 0.000 -0.000
[ WARN] [1657271537.253910877]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 5.3709 seconds
[ WARN] [1657271537.996695263]: Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.1199 seconds
[ WARN] [1657271538.183488184]: Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.1868 seconds
[ WARN] [1657271538.306957356]: Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.1235 seconds
[ERROR] [1657271538.364497784]: Extrapolation Error: Lookup would require extrapolation into the future.  Requested time 1657271538.282646894 but the latest data is at time 1657271538.267853389, when looking up transform from frame [rosbot1/odom] to frame [map]

[ERROR] [1657271538.364693355]: Global Frame: rosbot1/odom Plan Frame size 60: map

[ WARN] [1657271538.364798321]: Could not transform the global plan to the frame of the controller
[ WARN] [1657271543.264817958]: Map update loop missed its desired rate of 0.5000Hz... the loop actually took 6.0111 seconds
[ WARN] [1657271544.060753174]: Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.2038 seconds
[ WARN] [1657271544.212232593]: Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.1515 seconds
[ WARN] [1657271544.382020107]: Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.1698 seconds
[ WARN] [1657271544.481722016]: Control loop missed its desired rate of 20.0000Hz... the loop actually took 0.0997 seconds
[ERROR] [1657271544.516467207]: Extrapolation Error: Lookup would require extrapolation into the future.  Requested time 1657271544.478997946 but the latest data is at time 1657271544.457345658, when looking up transform from frame [rosbot1/odom] to frame [map]

Could you please help me to have a check? Thanks in advance!

BRs,
Si

Hi,

I guess that’s an error when you don’t set use_sim_time as true before starting the launch file or when yours nodes are unsynchronized. Have you perhaps tried following these instructions?

Best regards,
Paweł