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

Got confused with frame_ids

asked 2018-01-13 15:42:13 -0500

ZanaZak gravatar image

updated 2018-01-17 03:31:29 -0500

I'm fusing GPS, Visual Odometry and IMU. After reading the documentations with some try and error tests, finally I can get a reasonable output.

I put the frame_id of my Visual Odometry output as odom. I put the frame_id of my IMU as base_link. The GPS data is transformed to odom frame using navsat_transform_node and all three sensors are fused in ekf_node. Because Visual Odometry and GPS both produce x,y,z in state vector, I put differential mode to true for visual odometry as it is less accurate than GPS. I want you to explain me if this configuration is wrong. (I will send my launch file if you need)

Anyway

I'm confused about coordinate frames. The first time I read about the package, I though that it can handle multiple sensors in their own coordinate frames. I thought that It includes some sort of self-calibration. But Now, what I get is that the package only can produce /tf message between odom and base_link frames.

Is this true? I mean if I want to fuse a sensor in another frame, say odom_b, then do I have to provide /tf from odom_b to odom?

Next question: I know that visual odometry becomes less and less accurate over time. When I publish its poses, I just put the covariance of current measure and don't account for previous covariances. Does the filter accumulates those covariances it self?

<launch>

<node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" respawn="true">

  <param name="magnetic_declination_radians" value="0"/>

  <param name="yaw_offset" value="0"/>
  <param name="zero_altitude" value="true"/>

  <remap from="/imu/data" to="/imu_with_cov" />
  <remap from="/gps/fix" to="/fix" />
  <remap from="/odometry/filtered" to="/odometry/filtered" />

</node>

<node pkg="robot_localization" type="ukf_localization_node" name="ukf_se" clear_params="true">

<!-- ======== STANDARD PARAMETERS ======== -->

<param name="frequency" value="10"/>

<param name="sensor_timeout" value="0.1"/>

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

<!-- Defaults to "odom" if unspecified -->
<param name="odom_frame" value="odom"/>
<!-- Defaults to "base_link" if unspecified -->
<param name="base_link_frame" value="imu_link"/>
<!-- Defaults to the value of "odom_frame" if unspecified -->
<param name="world_frame" value="odom"/>

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

<param name="odom0" value="/vo"/>
<param name="odom1" value="/odometry/gps"/>
<param name="imu0" value="/imu_with_cov"/>

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

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

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

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

<param name="odom0_relative" value="true"/>
<param name="odom1_relative" value="true"/>
<param name="imu0_relative" value="true"/>

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

<!-- ======== ADVANCED PARAMETERS ======== -->

<param name="odom0_queue_size" value="5"/>
<param name="odom1_queue_size" value="50"/>
<param name="imu0_queue_size" value="50"/>

<param name="debug"           value="false"/>

<param name="debug_out_file"  value="debug_ekf_localization.txt"/>

</node>

<node pkg="my_mono_vo" type="monocularVO" name="monocularVO" respawn="true">

</node>

</launch>

EDIT1:

Hi Tom ... (more)

edit retag flag offensive close merge delete

Comments

2

Please post your full launch file, and a sample message for every input (e.g., your NavSatFix message, your IMU message, and your visual odometry message).

Tom Moore gravatar image Tom Moore  ( 2018-01-14 05:51:18 -0500 )edit

Great! Would you mind accepting the answer below? Just click the checkmark.

Tom Moore gravatar image Tom Moore  ( 2018-01-17 03:10:11 -0500 )edit

1 Answer

Sort by » oldest newest most voted
4

answered 2018-01-14 06:26:51 -0500

Tom Moore gravatar image

updated 2018-01-16 03:14:06 -0500

I put the frame_id of my Visual Odometry output as odom. I put the frame_id of my IMU as base_link. The GPS data is transformed to odom frame using navsat_transform_node and all three sensors are fused in ekf_node. Because Visual Odometry and GPS both produce x,y,z in state vector, I put differential mode to true for visual odometry as it is less accurate than GPS. I want you to explain me if this configuration is wrong.

It's always very helpful to post launch files AND sample input messages (preferably collected when your robot is moving) for questions about r_l. Without them, I can't really comment with any certainty about what your optimal setup is. This leads to two questions:

  1. Does your visual odometry produce velocity data, i.e., is the Twist section of the message filled out? If it does, then set X, Y, and Z to false in the config file for visual odometry, and set , , and Ż (the velocities for XYZ) to true.

    If your visual odometry only produces pose data, then yes, set the visual odometry differential parameter to true.

  2. How is your IMU mounted? If it's upside-down or sideways or rotated on its side, then having its frame as base_link is not going to work well.

I'm confused about coordinate frames. The first time I read about the package, I though that it can handle multiple sensors in their own coordinate frames. I thought that It includes some sort of self-calibration. But Now, what I get is that the package only can produce /tf message between odom and base_link frames.

I would thoroughly read REP-105 to start. The package can handle sensors in their own coordinate frames, certainly, but the package's job is to provide a transform from your world_frame to your base_link_frame in your configuration file. In your case, it's producing odom->base_link. That is the only transform that r_l produces.

However, it still works with data in any coordinate frame, provided you tell it how to transform from that coordinate frame to your world_frame or base_link_frame. Let's say, for example, that your IMU is mounted upside-down on your robot and is placed on the back end of the robot. This means that your IMU's coordinate frame is not base_link, since it's not at your robot's origin. That means you must provide, via URDF + robot_state_publisher or via a tf static_transform_publisher, a transform from base_link->imu, and then set the frame_id in your IMU messages to imu. When r_l receives the IMU message, it will see that its frame_id is IMU, and will try to transform it to base_link.

So: if you are fusing pose data, you need to make sure there's a transform from your sensor message's frame_id to your world_frame. If you are fusing velocity data, then you need to make sure that there's a transform from your sensor's child_frame_id (for nav_msgs/Odometry messages) or frame_id ... (more)

edit flag offensive delete link more

Comments

you must provide, via URDF/robot_state_publisher

shouldn't that be: "via URDF + robot_state_publisher"? URDF on its own doesn't do much, and neither does robot_state_publisher. They're going to need each other :)

gvdhoorn gravatar image gvdhoorn  ( 2018-01-14 06:41:22 -0500 )edit

Sorry, yes, I was using the / to treat them as a group. Will clarify, TY.

Tom Moore gravatar image Tom Moore  ( 2018-01-14 07:07:02 -0500 )edit
2

Can't upvote this more than once, but +100 for analysing these posts with such detail every time @Tom Moore.

Seems sensor fusion is not easy, and ROS new comers and experienced users need quite some help.

gvdhoorn gravatar image gvdhoorn  ( 2018-01-15 06:27:27 -0500 )edit

Thanks, @gvdhoorn. I should really take these questions as an opportunity to improve the wiki. I also wish ROS Answers were easier to search, because I find I often answer similar sorts of questions. I know you can use Google, but I wish that the native search were as powerful.

Tom Moore gravatar image Tom Moore  ( 2018-01-15 10:16:55 -0500 )edit

re: update wiki: yes, a faq might be an idea? Would save you from some typing perhaps. Although I've experienced that you can't always just point to a faq item unfortunately.

re: search: ros-infrastructure/answers.ros.org#155.

gvdhoorn gravatar image gvdhoorn  ( 2018-01-15 10:24:42 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-01-13 15:42:13 -0500

Seen: 765 times

Last updated: Jan 17 '18