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

How is the orientation of frame /odom initialized?

asked 2016-05-25 21:31:41 -0500

M@t gravatar image

updated 2016-06-30 16:47:41 -0500

What determines the orientation of the tf frame /odom when it is initialized?

On the page for GPS integration, here. It says:

"The odom and map frames are world-fixed frames and generally have their origins at the vehicle's start position and orientation."

However I have personally found that while the position of /odom and /base_link match at startup, the orientation doesn't. In the image below all I have done is move the robot directly forward, and you can see that it's orientation (/base_link) does not match that of /odom.

tf /base_link

So, if it isn't being initialized to match /base_link, how is it being initialized? Or is this a bug?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
5

answered 2016-05-30 05:48:55 -0500

Tom Moore gravatar image

updated 2016-06-01 01:31:15 -0500

It looks like you're using a simulated Jackal. Looking at the r_l config for the Jackal, you can see that the yaw data from the IMU is being fused. Therefore, if at time t0, your simulated IMU reports a non-zero yaw, then the filter is going to reflect that. If you want it to start with 0 yaw even when the IMU doesn't, turn on relative mode for that sensor (i.e., imu0_relative: true).

Edit in response to comments

First, the template launch file is just that: a template. It's meant to show you what parameters are available to you, but isn't actually used by the nodes in r_l. The various parameters, where appropriate, do have default values if not specified, and you are correct that the _relative parameter defaults to false.

Second, note that moving the odom frame origin is equivalent to setting the robot's pose in the odom frame. You can use the set_pose service for that.

edit flag offensive delete link more

Comments

Ah, I think I understand. But I'm actually using a real Jackal, and I see that in ekf_template.launch this variable is already set to true, whereas in robot_localization.yaml it's undefined. So am I correct in assuming it defaults to false and robot_localization.yaml overrides ekf_template.launch?

M@t gravatar image M@t  ( 2016-05-31 18:51:08 -0500 )edit

Yeap, that did the trick. Adding imu0_relative: true to robot_localization.yaml forces the /odom frame to align with /base_link. Is there also a way to explicitly set the origin and orientation of /odom the same way you can with /utm using navsat_transform_node?

M@t gravatar image M@t  ( 2016-05-31 19:15:01 -0500 )edit
2

answered 2016-06-21 19:22:01 -0500

M@t gravatar image

updated 2016-07-06 21:03:36 -0500

Tom Moore's answer is correct, however for others like me who are relatively new to ROS I'll restate everything a bit more explicitly with instructions. In this instance I am referring to the frame /odom as created by an instance of ekf_localization from the robot_localization package, so my explanation relates to that package. The problem and solution may be different if you are using some other part of the navigation stack to track odometry. I'm also assuming that this is a ground based robot with IMU and odometry data.

Problem

You want to know how the frame /odom is initialized and how you can manually re-set it or control it's initialization.

Cause

In short: The origin of /odom initializes to the current position of the robot. The orientation of /odom initializes to whatever your IMU thinks is magnetic North (the heading at which your IMU reads 0.0).

In full: The frame /odom is created by an instance of ekf_localization when the node is launched. By default, the origin of /odom is set equal to the origin of /base_link - i.e. the current position of your robot. The ekf_localization node requires an IMU data stream as an input (default source is /imu/data). This data stream dictates the orientation of /odom. When ekf_localization is launched it will read the IMU data and set the orientation of /odom to whatever heading your IMU will read 0.0 at. If your IMU data is earth-referenced, it will (typically) read 0.0 when pointing to magnetic North. So, your /odom frame will initialize with its orientation pointing to magnetic North.

However, you may want to re-set /odom or otherwise control its pose...

Solution

There are three things you can do to set the origin and orientation of /odom:

  1. Initialize /odom to match the origin and orientation of /base_link at launch.
  2. Manually re-set the origin and orientation of /odom by publishing a geometry_msgs/PoseWithCovarianceStamped to the /set_pose topic.
  3. Use the SetPose service to set the origin and orientation.

(There may be more options that I don't know about yet so feel free to correct me)

Setting /odom at launch

This is as simple as setting a single parameter in the launch file for your robot_localization instance that is creating /odom. Find your launch file and add the line:

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

To override the IMU data and match the orientations. The origin of /odom should already match.

Re-setting /odom by publishing to /set_pose

At any time you can publish a geometry_msgs/PoseWithCovarianceStamped message to the /set_pose topic. The topic likely won't appear using rostopic list until you publish to it. Type this into a terminal:

rostopic pub /set_pose geometry_msgs/PoseWithCovarianceStamped '{header: {stamp: now, frame_id: "odom"}, pose: {pose: {position: {x: 1.0, y: 1.0, z: 0.0}, orientation: {w: 1.0} }, covariance: [1,0,0,0,0,0,0,1,0,0,0,0,0,0,1,0,0,0,0,0,0,1,0,0 ...
(more)
edit flag offensive delete link more

Comments

Use the SetPose servicerosservice call /set_pose <tab> . will let you modify the message manually.

asimay_y gravatar image asimay_y  ( 2016-06-21 22:37:24 -0500 )edit

Question Tools

5 followers

Stats

Asked: 2016-05-25 21:31:41 -0500

Seen: 4,742 times

Last updated: Jul 06 '16