I have a Broadcaster from a base_link to a imu_link frame. But in Robot Localization i "can not obtain the transform"

asked 2020-07-22 10:08:39 -0500

HaiKai gravatar image

Hello,

I am trying to use a EKF in the robot localization package to fuse a global localization method with an imu and a visual odometry. To limit the area of the Warning, i reduced this system, so i have only one imu sensor as an input sensor for the robot localization. If i'm trying to run the Kalman Filter, this Warning in the output on the screen occurs:

process[convert_imu_imuWithCovariance-1]: started with pid [14128]
process[ekf_imu-2]: started with pid [14129]

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

[ WARN] [1595427144.180960357]: Transform from imu_link to base_link was unavailable for the time requested. Using latest instead.

[ WARN] [1595427146.188093633]: Transform from imu_link to base_link was unavailable for the time requested. Using latest instead.

... and so on.

As you can see in this output, i run a node "convert_imu_imuWithCovariance" befor the EKF starts. In this node i'm preparing the sensor data of the imu and included the broadcaster between the base_link and the imu_frame. Here you can see this file:

#!/usr/bin/env python
import rospy
import tf
from sensor_msgs.msg import Imu

def callback(imu_data):

    imu_WithCovariance = Imu()
    imu_WithCovariance = imu_data
    imu_WithCovariance.header.frame_id = 'imu_link'

    imu_WithCovariance.orientation_covariance = [0.02, 0, 0, 0, 0.02, 0, 0, 0, 0.02]
    imu_WithCovariance.angular_velocity_covariance = [0.02, 0, 0, 0, 0.02, 0, 0, 0, 0.02]
    imu_WithCovariance.linear_acceleration_covariance = [0.1, 0, 0, 0, 0.1, 0, 0, 0, 0.1]

    pubImuWithCovariance = rospy.Publisher('imuWithCovariance', Imu, queue_size=10)
    pubImuWithCovariance.publish(imu_WithCovariance)

    br = tf.TransformBroadcaster()
    br.sendTransform((0.0, 0.0, 0.0),
                     (0.0, 0.04716514, 0.04400028, 0.99791754),
                     imu_data.header.stamp,
                     "imu_link",
                     "base_link")

def convert_imu_information():

    rospy.init_node('convert_imu_imuWithCovariance', anonymous=True)
    rospy.Subscriber("/imu/data", Imu, callback)

    rospy.spin()

if __name__ == '__main__':

    convert_imu_information()

And here is the appropriate launch file:

  <launch>

    <node name="convert_imu_imuWithCovariance" pkg="rabe_localization2" type="convert_imu_imuWithCovariance.py" respawn="false" output="screen" />

    <rosparam command="load" file="$(find only_imu)/config/only_imu.yaml" />

    <node pkg="robot_localization" type="ekf_localization_node" name="ekf_imu" clear_params="true"/>

  </launch>

And the corresponding file for the parameter defination of robot localization (in this post i've removed the process_noise_covariance and the initial_estimate_covariance for a better overview):

ekf_imu:
  frequency: 100
  sensor_timeout: 0.03
  two_d_mode: true
  transform_time_offset: 0.0
  transform_timeout: 0.0
  print_diagnostics: true
  debug: false

  map_frame: telocate
  odom_frame: odom
  base_link_frame: base_link
  world_frame: odom

  imu0: imuWithCovariance
  imu0_config: [false, false, false,
                true,  true,  true,
                false, false, false,
                true,  true,  true,
                true,  true,  true]
  imu0_nodelay: false
  imu0_differential: false
  imu0_relative: false
  imu0_queue_size: 10
  imu0_remove_gravitational_acceleration: true

  use_control: false

  process_noise_covariance: [...]

  initial_estimate_covariance: [...]

After running

rosrun tf tf_echo imu_link base_link

I saw, that there is a transformation. This one can also be seen in the file receiving from

rosrun tf view_frames

Which will be added here:

Because i run the sensor data from a bag file, where also the other sensor information are included, in the shown frames file only the left part is important.

I've saw, that there are a ... (more)

edit retag flag offensive close merge delete