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

robot_localization TF problem

asked 2015-09-24 09:10:32 -0500

higorbarb gravatar image

updated 2015-09-24 17:34:54 -0500

Hi there, I'm using ROS Indigo with V-REP simulator and robot_localization to fuse odom and imu data. I start the ekf_localization_node, it does not display an error message, but does not publish anything. Already, the debug file shows "Could not transform measurement into odom. Ignoring..." and "Could not transform measurement into base_link. Ignoring...". V-REP publishes TF tree: map->odom->base_link->sparton. I checked tf and it's being made correctly. What's wrong? The launch file is:

<launch>
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true">
  <param name="frequency" value="30"/>
  <param name="sensor_timeout" value="0.1"/>
  <param name="two_d_mode" value="false"/>

  <param name="map_frame" value="/map"/>
  <param name="odom_frame" value="/odom"/>
  <param name="base_link_frame" value="/base_link"/>
  <param name="world_frame" value="/odom"/>

  <param name="transform_time_offset" value="0.0"/>

  <param name="odom0" value="/air2/odom"/>
  <param name="imu0" value="/air2/imu"/>

  <rosparam param="odom0_config">[true,  true,  true,
                                  true,  true,  true,
                                  false, false, false,
                                  true,  true,  true,
                                  false, false, false]</rosparam>

  <rosparam param="imu0_config">[false, false, false,
                                 true,  true,  true,
                                 false, false, false,
                                 true,  true,  true,
                                 true,  true,  true]</rosparam>

  <param name="odom0_differential" value="true"/>
  <param name="imu0_differential" value="true"/>

  <param name="odom0_relative" value="false"/>
  <param name="imu0_relative" value="false"/> 

  <param name="imu0_remove_gravitational_acceleration" value="true"/>

  <param name="print_diagnostics" value="true"/>

  <param name="odom0_queue_size" value="10"/>
  <param name="imu0_queue_size" value="10"/>

  <param name="debug"           value="true"/>
  <param name="debug_out_file"  value="/home/robo/debug_ekf_localization.txt"/>
</node>

</launch>

Odom topic:

header: 
  seq: 98
  stamp: 
    secs: 1443031642
    nsecs: 362367329
  frame_id: /odom
child_frame_id: /base_link
pose: 
  pose: 
    position: 
      x: -0.00514762103558
      y: 0.00168874696828
      z: 0.0593957901001
    orientation: 
      x: -0.707533717155
      y: 0.0267585106194
      z: 0.0170629229397
      w: -0.70596665144
  covariance: [0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513]
twist: 
  twist: 
    linear: 
      x: -0.0889131724834
      y: 0.0042970222421
      z: -2.02671504021
    angular: 
      x: -0.321618080139
      y: 4.16820764542
      z: -3.00630068779
  covariance: [0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010000000474974513]

IMU topic:

header: 
  seq: 80
  stamp: 
    secs: 1443102518
    nsecs: 982325656
  frame_id: /sparton
orientation: 
  x: 0.476446002722
  y: 0.473839610815
  z: 0.526966273785
  w: -0.520367085934
orientation_covariance: [9.999999974752427e-07, 0.0, 0.0, 0.0, 9.999999974752427e-07, 0.0, 0.0, 0.0, 9.999999974752427e-07]
angular_velocity: 
  x: 0.000786931079347
  y: -0.00079421402188
  z: 0.00557178910822
angular_velocity_covariance: [9.999999974752427e-07, 0 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-09-25 07:50:46 -0500

Tom Moore gravatar image

updated 2015-09-25 07:51:57 -0500

Two things.

  1. V-REP publishes TF tree: map->odom->base_link->sparton. I checked tf and it's being made correctly.

    It is ekf_localization_node's job to publish the odom->base_link transform or the map->odom transform (depending on what you have world_frame set to). If some other node is publishing them, that's a problem.

  2. Get rid of the forward slashes in the frame_id fields of your input messages. ekf_localization_node uses tf2, and so it automatically strips leading forward slashes from your *_frame parameters in the launch file. See this.

edit flag offensive delete link more

Comments

Thanks Moore, I removed the forward slashes in the frame_id of messages and it worked.

higorbarb gravatar image higorbarb  ( 2015-09-26 08:56:22 -0500 )edit

@Tom Moore Do you mean that robot_localization can not be used with other SLAM packages like hector_mapping, karto_slam at the same time? Since these SLAM packages publish map->odom. Thanks!

scopus gravatar image scopus  ( 2017-12-04 23:49:57 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-09-24 09:10:32 -0500

Seen: 1,053 times

Last updated: Sep 25 '15