Create3, wheel transform in Gazebo classic

asked 2022-05-01 14:59:18 -0500

maurizio gravatar image

updated 2022-05-01 15:00:44 -0500

Hi,

I have installed the Create3 simulation stack. In particular these are the "heads":

create3_sim: commit d8a6919d7d5df4d1dce8fe9978fe156080a60d0b (HEAD -> main, origin/main, origin/HEAD) irobot_create_msgs: commit dbc85d9a91d105799d983569796cf1a9ff2fc34d (HEAD, tag: 1.2.4, origin/main, origin/galactic, origin/HEAD, main)

When I launch a simulation in Gazebo classic (empty world):

ros2 launch irobot_create_gazebo_bringup create3_gazebo.launch.py

Rviz complains about the wheels (left/right) frames not being related to odom (see the attached picture). Taking a look to the xacro files I can see that they are related to base_link as confirmed by the transform tree obtained by the following command:

ros2 run tf2_tools view_frames

Furthermore I can see that the relation seems to be there (odom->base_link + base_link->left_wheel - I am not reporting the intermediate links with drop_wheel_[left|right] to keep it simpler):

ros2 run tf2_ros tf2_echo   odom base_link                         ====>   ODOM -> BASE_LINK
At time 82.29000000
- Translation: [-0.000, 0.000, 0.000]
- Rotation: in Quaternion [0.000, 0.000, -0.000, 1.000]


ros2 run tf2_ros tf2_echo  base_link left_wheel                     ====> BASE_LINK -> LEFT_WHEEL
- Translation: [0.000, 0.117, 0.040]
- Rotation: in Quaternion [-0.707, 0.000, 0.000, 0.707]
At time 1651430929.241857047
- Translation: [0.000, 0.117, 0.040]
- Rotation: in Quaternion [-0.707, 0.000, 0.000, 0.707]
At time 1651430930.241933452
- Translation: [0.000, 0.117, 0.040]
- Rotation: in Quaternion [-0.707, 0.000, 0.000, 0.707]

But when trying to get the direct relation, I get:

ros2 run tf2_ros tf2_echo   odom left_wheel

[INFO] [1651433130.773527298] [tf2_echo]: Waiting for transform odom ->  left_wheel: Lookup would require extrapolation into the past.  Requested time 22.035000 but the earliest data is at time 1651433128.812717, when looking up transform from frame [left_wheel] to frame [odom]

Where the 'weird' timestamp is the actual epoch time when I ran the simulation.

Looking at this and that, it seems that not all the nodes are set to use the sim time: I have tried to add in the gazebo_params.yaml file the parameter: gazebo:

  ros__parameters:
    publish_rate: 62.0
    use_sim_time: True

But that doesn't help. From what I see the file irobot_create_control/share/irobot_create_control/config/control.yaml has it already set. Trying to set it in irobot_create_common/irobot_create_common_bringup/config/wheel_status_params.yaml doesn't help either...

Do you have any suggestion?

Thanks for the attention

C:\fakepath\problem.png

edit retag flag offensive close merge delete