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

Husky Gazebo robot_state_publisher not broadcasting transforms

asked 2020-04-20 19:23:49 -0600

luketheduke gravatar image

I'm trying to record a bag from the Husky Gazebo simulation for Cartographer SLAM on Kinetic and Ubuntu 18.04 VM. The problem I'm facing is that some of the TF transforms are not being included in the bag file. Here's the steps I took: Launch the simulator: roslaunch husky_gazebo husky_playpen.launch This correctly launches the simulator. I can control it with key_teleop and tf/view_frames gives this result: image description Here's a close up of the problem area: image description When I record a bag with rosbag record -O Husky /tf /odometry/filtered /scan I can successfully record the messages and drive the robot around to get simulated data for SLAM, but when playing it back, tf/view_frames looks like this: image description The TF tree is missing large parts, including the base_laser link, which is the one I need. I think the error is that robot_state_publisher is not sending out TF transforms. Even though the average rate is 10,000 hz, the last message was registered as 1300 seconds before, even though the simulator hasn't been up that long. How do I resolve this so that those transforms are included in the bag? It doesn't appear to be dying in the console, here's the output when I start the sim:

    process[gazebo-1]: started with pid [9282]
process[gazebo_gui-2]: started with pid [9287]
process[base_controller_spawner-3]: started with pid [9292]
process[ekf_localization-4]: started with pid [9293]
process[twist_marker_server-5]: started with pid [9299]
process[robot_state_publisher-6]: started with pid [9309]
process[twist_mux-7]: started with pid [9319]
process[spawn_husky_model-8]: started with pid [9327]
[ INFO] [1587427802.385761428]: [twist_marker_server] Initialized.
[ INFO] [1587427802.503502938]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1587427802.504856515]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1587427802.539750475]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1587427802.541527633]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1587427803.728679997, 1298.500000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1587427803.811557590, 1298.570000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
Warning [parser_urdf.cc:1232] multiple inconsistent <gravity> exists due to fixed joint reduction overwriting previous value [true] with [false].
[ INFO] [1587427804.993717048, 1298.670000000]: Laser Plugin: Using the 'robotNamespace' param: '/'
[ INFO] [1587427804.993776607, 1298.670000000]: Starting Laser Plugin (ns = /)
[ INFO] [1587427804.995091901, 1298.670000000]: Laser Plugin (ns = /)  <tf_prefix_>, set to ""
[ INFO] [1587427805.019063308, 1298.670000000]: Physics dynamic reconfigure ready.
[ INFO] [1587427805.020134181, 1298.670000000]: Physics dynamic reconfigure ready.
[ INFO] [1587427805.107275723, 1298.670000000]: Loading gazebo_ros_control plugin
[ INFO] [1587427805.107442330, 1298.670000000]: Starting gazebo_ros_control plugin in namespace: /
[ INFO] [1587427805.108631669, 1298.670000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [robot_description] on the ROS param server.
[ERROR] [1587427805.223508597, 1298.670000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/front_left_wheel
[ERROR] [1587427805.225517904, 1298.670000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/front_right_wheel
[ERROR] [1587427805.227545101, 1298.670000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/rear_left_wheel
[ERROR] [1587427805.229322958, 1298.670000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/rear_right_wheel
[ INFO] [1587427805 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-04-21 05:43:20 -0600

gvdhoorn gravatar image

updated 2020-04-21 05:44:18 -0600

When I record a bag with rosbag record -O Husky /tf /odometry/filtered /scan [..]

what about /tf_static?

Even though the average rate is 10,000 hz

those are most likely static frames, which don't get broadcast periodically. They're given a 'fake' rate of 10kHz.

edit flag offensive delete link more

Comments

I didn't know those existed. I relaunched the sim and echoed the /tf_static topic and all the missing transforms are there, so that was the problem, thanks for the help!

luketheduke gravatar image luketheduke  ( 2020-04-21 09:44:25 -0600 )edit

As gvdhoorn pointed out, I wasn't recording /tf_static and that meant that I wasn't recording any static TF transforms, which were the ones that were missing. So the fix was just to rerecord with rosbag record -O Husky /tf /tf_static /odometry/filtered /scan

luketheduke gravatar image luketheduke  ( 2020-04-21 09:45:42 -0600 )edit

I've converted my comment to an answer. Wanted to make sure it was the problem before posting an answer.

gvdhoorn gravatar image gvdhoorn  ( 2020-04-21 09:53:11 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2020-04-20 19:23:49 -0600

Seen: 665 times

Last updated: Apr 21 '20