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

robot_localization does not produce odom->base_link transform

asked 2016-07-10 23:16:07 -0500

mohakbhardwaj gravatar image

updated 2016-07-13 16:49:47 -0500

Hello everyone, I have been searching for a long time for my problem but still have not found a solution. I am using robot_localization with IMU data. My imu data is published to a topic /inertial_data with frame_id = "imu". The following is my configuration file

frequency: 30

sensor_timeout: 0.1

transform_time_offset: 0.0

two_d_mode: false

print_diagnostics: true

debug: false
debug_out_file: /home/mohak/catkin_ws/debug_file.txt

map_frame: map
odom_frame: odom
base_link_frame: base
world_frame: odom

use_control: true
stamped_control: false
control_timeout: 0.2
control_config: [true, false, false, false, false, true]
acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]
deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]
acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]
deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]

imu0: /inertial_data
imu0_config: [false, false, false,
              false,  false,  false,
              false, false, false,
              true,  true,  true,
              true,  true,  true]
imu0_nodelay: false

imu0_queue_size: 5
imu0_pose_rejection_threshold: 0.8
imu0_twist_rejection_threshold: 0.8
imu0_linear_acceleration_rejection_threshold: 0.8

process_noise_covariance: [0.05, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,
                           0,    0.05, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,
                           0,    0,    0.06, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,
                           0,    0,    0,    0.03, 0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,
                           0,    0,    0,    0,    0.03, 0,    0,     0,     0,    0,    0,    0,    0,    0,    0,
                           0,    0,    0,    0,    0,    0.06, 0,     0,     0,    0,    0,    0,    0,    0,    0,
                           0,    0,    0,    0,    0,    0,    0.025, 0,     0,    0,    0,    0,    0,    0,    0,
                           0,    0,    0,    0,    0,    0,    0,     0.025, 0,    0,    0,    0,    0,    0,    0,
                           0,    0,    0,    0,    0,    0,    0,     0,     0.04, 0,    0,    0,    0,    0,    0,
                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0.01, 0,    0,    0,    0,    0,
                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.01, 0,    0,    0,    0,
                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.02, 0,    0,    0,
                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.01, 0,    0,
                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.01, 0,
                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.015]

initial_estimate_covariance: [1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,
                              0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,
                              0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,
                              0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,
                              0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,
                              0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0 ...
(more)
edit retag flag offensive close merge delete

Comments

Can you post a tf tree of the frames you've got? There are several things that I suspect might be wrong like running static_transform_publisher that broadcasts the imu->base which is obviously wrong or even base_link_frame which is "base"... but first post that tf tree!

Arwen gravatar image Arwen  ( 2016-07-13 02:25:48 -0500 )edit

@Arwen I have edited the answer to include an image of the tf tree. It shows the odom frame being published as not connected to any other frame but as a floating frame. The static transform publisher is used to publish the transform from the location where the imu is mounted on the system to the bas

mohakbhardwaj gravatar image mohakbhardwaj  ( 2016-07-13 12:49:01 -0500 )edit

It's a little spooky... your robot_localization parameters seem fine but it's strange that the tf tree shows that imu -> base is being broadcast by ekf_se, you may wanna post your robot_localization launch file and exact line you're using for running static_transform_publisher.

Arwen gravatar image Arwen  ( 2016-07-13 15:04:31 -0500 )edit

@Arwen: Yes that seems very unnatural to me as well. I have included links the launch files in my original post now. I have a data_publisher package which has the responsibility of publishing the imu data (only rotation rates and linear accelerations in my case) as a sensor_msgs/Imu message

mohakbhardwaj gravatar image mohakbhardwaj  ( 2016-07-13 16:52:02 -0500 )edit

2 Answers

Sort by » oldest newest most voted
1

answered 2016-07-14 00:40:19 -0500

Arwen gravatar image

Thanks to the information you've provided now I can help you solve your problem.

The ekf_localization_node that you run provides the transformation between odom and base, the static_transform_publisher instance also broadcasts transformation between imu and base. So this will be the result:

odom -> base , imu -> base

while the correct tf tree must be like this:

odom -> base -> imu

Your base frame has two parents which is clearly not possible. Each frame can only have one parent.

In your case, you are running static_transform_publisher with wrong input parameters.

    <node pkg="tf" type="static_transform_publisher" name="imu_to_robot_base" args="0 0 0 0 0 0 $(arg imu_frame_id) base 100" />

Just switch the parent and child frame in the input arguments and your problem should be solved. The result must be like this:

    <node pkg="tf" type="static_transform_publisher" name="imu_to_robot_base" args="0 0 0 0 0 0 base $(arg imu_frame_id) 100" />
edit flag offensive delete link more

Comments

Thanks! It is now publishing the transform. I have one confusion thought, is there anything in the parameters file that I am missing for the robot_localization package to compute x,y,z position from the rates and accelerations only? It is constantly publishing the x,y,z position as zero

mohakbhardwaj gravatar image mohakbhardwaj  ( 2016-07-14 13:34:32 -0500 )edit

@mohakbhardwaj: I think you should start with a simpler configuration, currently you have set several advanced parameters and finding the exact problem is not that easy. By the way I haven't tested robot_localization with only a single imu, but I don't think the result would be satisfying.

Arwen gravatar image Arwen  ( 2016-07-15 01:38:50 -0500 )edit
0

answered 2016-07-14 03:13:36 -0500

asimay_y gravatar image

updated 2016-07-14 03:13:50 -0500

should be:

map_frame: odom
base_link_frame: base_link
publish_tf: true
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2016-07-10 23:16:07 -0500

Seen: 2,087 times

Last updated: Jul 14 '16