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

Integrate an IMU sensor with robot_localization

asked 2014-11-27 07:42:00 -0500

ASoriano gravatar image

updated 2014-12-22 11:56:53 -0500

Hello,

I'm trying to integrate an IMU sensor to my mobile robot no holonomic.

I follow the robot_localization tutorial to do that, but I'm a little confused with some questions.

  • First, how should be my resulting tf tree? I think the frame "odom_ekf" provided from ekf_localization node would be at the top of the tree. The base_link frame would be down. So when I called the set_pose service provided from ekf_localization node, this service could changed the values of transformed between "odom_ekf" frame and "base_link" frame. Is that correct?

  • Second, only starting to fuse the IMU sensor with the odometry, how the launch file of robot_localization should be?

    <launch>
    <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true" output="screen">
    
      <param name="frequency" value="30"/>
      <param name="sensor_timeout" value="0.1"/>
    
      <param name="odom_frame" value="odom_ekf"/>
      <param name="base_link_frame" value="base_link"/>
      <param name="world_frame" value="odom_ekf"/>
    
      <param name="odom0" value="/myOdomTopic"/>
      <param name="imu0" value="/myImuTopic"/>
      <rosparam param="odom0_config">[false, false, true,
                                      true, true, true,
                                      true, true,true,
                                      true, true, true,
                                      true, true, true]</rosparam>
    
      <rosparam param="imu0_config">[false, false, false,
                                     true,  true,  true,
                                     false, false, false,
                                     false, false, false,
                                     true,  true,  true]</rosparam>
    
      <param name="imu0_remove_gravitational_acceleration" value="true"/>
      <param name="odom0_remove_gravitational_acceleration" value="true"/>
    
      <param name="odom0_differential" value="true"/>
      <param name="imu0_differential" value="false"/>
      <remap from="/odometry/filtered" to="/odometry/odom_imu" />
    
     </node>
    </launch>
    

With this launch, the tf between odom_ekf and base_link is published and the topic /odometry/filtered shows correctly the robot position. But:

- The topic /odometry/filtered doesn't take into a count the changes at orientation. The position is more or less fine, but the orientation doesn't change. - The remap to /odometry/odom_imu is not working. - When the robot_localization is running these warnings appears constantly:

"[ WARN] [1417095211.082070235]: MessageFilter [target=odom_ekf ]: Dropped 100.00% of messages so far. Please turn the [ros.robot_localization.message_notifier] rosconsole logger to DEBUG for more information. I think first I have to solve this problems and then integrate the GPS sensor.

I'm not sure what I'm doing wrong. Some help would be greatly appreciated.

UPDATE 1:

Here is my frames.pdf

I've corrected some errors with the tf and now the robot_localization node doesn't show any errors.

The problem now is that the odometry/filetered isn't given the correct position and orientation. This is my launch file:

<launch>
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true" output="screen">
<param name="frequency" value="30"/>
<param name="sensor_timeout" value="0.1"/>
  <param name="odom_frame" value="summit_a/odom"/>
      <param name="base_link_frame" value="summit_a/base_footprint"/>
<param name="world_frame" value="summit_a/odom"/>
<param name="odom0" value="summit_xl_controller/odom"/>
 <rosparam param="odom0_config">[true, true, false,
                                      false, false, true,
                                      true, true, false,
                                      false, false, true,
                                      false, false, false]
                                      </rosparam>
<rosparam param="imu0_config">[false, false, false,
                                     false, false, false,
                                     false, false, false,
                                     false, false, true,
                                     false, false, false]</rosparam>
  <param name="two_d_mode" value="true"/>
      <param name="odom0_differential" value="true"/>
<param name="imu0_differential" value="true"/>
   </node>
</launch>

The odometry of odom0 is ... (more)

edit retag flag offensive close merge delete

Comments

Question before I update the answer: is this robot holonomic? It doesn't look it, but I know the Summit XLs can have omnidirectional wheels.

Tom Moore gravatar image Tom Moore  ( 2014-12-09 14:44:37 -0500 )edit

Comment in response to update 3: I'll take a look at this. Just so I'm clear, for the path that you drove, the robot's real-world start and end locations were exactly the same, correct?

Tom Moore gravatar image Tom Moore  ( 2014-12-15 08:23:56 -0500 )edit

One more thing: I keep getting errors when I attempt to filter your ROS bag files. This happened for the last file as well. The error is long, but here's the last line of it:

UnicodeDecodeError: 'ascii' codec can't decode byte 0xc2 in position 4080: ordinal not in range(128)

Tom Moore gravatar image Tom Moore  ( 2014-12-15 08:36:31 -0500 )edit

The path that I drove finished more or less at the same location that started. Just the odometry (red) is so reliable, the odometry_filtered (green) should be very similiar to odometry(red).

ASoriano gravatar image ASoriano  ( 2014-12-15 10:37:36 -0500 )edit

I don't have any problem playing my bagfiles. I'm using hydro, maybe you're using indigo and something at bagfiles changed?

ASoriano gravatar image ASoriano  ( 2014-12-15 10:38:07 -0500 )edit

Great! I'm glad it's working for you. Do you mind if I use your bag file for generating new integration tests? I ask because it would likely become part of the package, at least until I locate some web space for storing them.

Tom Moore gravatar image Tom Moore  ( 2014-12-22 12:15:54 -0500 )edit

Of course. Feel free to use my bag file.

ASoriano gravatar image ASoriano  ( 2014-12-22 12:39:03 -0500 )edit

ASoriano, Do you have the file where you have fill the imu msg? I use rosserial_arduino to do that but I want to compare other methods. Thank you.

novak gravatar image novak  ( 2017-03-29 07:01:15 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
5

answered 2014-11-27 09:02:17 -0500

Tom Moore gravatar image

updated 2014-12-19 07:46:25 -0500

Before I start, it would be super helpful if you would also post sample messages from your odometry and IMU. Also, if you can, maybe post your tf tree?

To your questions:

  • If your world_frame is the same as your odom_frame (which is the case for you), then the node outputs a transform from your world_frame to your odom_frame. This transform is the same as the position that is output by the filter, so yes, if you call the set_pose service, the transform should also change.
  • Does your IMU provide only absolute orientation, or does it provide rotational velocity as well? Right now, you have it set for absolute orientation and linear acceleration only. If you wanted rotational velocity as well, do this:

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

    Unless you have good reason, set the imu0_differential setting to true. Will you be starting on an incline?

  • The warning is very telling. The issue is that the filter can't transform your IMU messages into the target tf frame. If you post your tf tree and a sample IMU message, that will help.

  • Side note 1: gravitational acceleration only applies to IMU topics. You can remove

    <param name="odom0_remove_gravitational_acceleration" value="true"/>
    
  • Side note 2: Your odometry configuration needs some tweaking. Is your robot operating in 2D or 3D? If it's 3D (or if you want to include subtle variations in the ground plane for a robot operating in 2D), then does your odometry data actually fill out roll, pitch, roll velocity, and pitch velocity? Also, your odometry data doesn't contain linear acceleration, so the last three true values are unnecessary. I'd have to see your odometry data to give you a more definitive answer, but for now, try this:

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

Fix those issues and post your messages and I can help more.

EDIT after update:

Two things:

- Looking at your rviz output, it seems as though one of your orientation data sources is producing headings (or heading velocities) that are the wrong sign. As per this page on the wiki, it's critical that you look at the output of each of your sensors, one at a time, and make sure that the signs are correct and in adherence with REP-103. If your robot turns left, that is positive yaw. You'll have to covert from quaternions in the messages to Euler angles (unless you're good at deciphering quaternions).

  • For your odometry data, use the velocity or use the absolute position. Don't use both. If your odometry source is generating body-frame velocities (and make sure they're in the body frame), then I'd go with those, and set X, Y, and yaw to false.

Fix those, and then let me know how it goes. If it's still ... (more)

edit flag offensive delete link more

Question Tools

7 followers

Stats

Asked: 2014-11-27 07:42:00 -0500

Seen: 5,613 times

Last updated: Dec 22 '14