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

Revision history [back]

Your IMU probably reads 0 at magnetic north. But we need a heading reference that aligns with the UTM grid, where +X points east, and +Y points north. That means we need our heading from the IMU to read 0 when the robot is facing east. So we have two parameters (technically we have 3, but one, the UTM meridian convergence, is accounted for automatically in the code):

  1. If we adjust for magnetic declination (using the magnetic_declination_radians parameter), we can get the IMU data to read 0 at true north, rather than magnetic north. But that means we have a heading of 0 when we face north, but we need it to be 0 when we face east, so...
  2. ...we need to adjust for that 90 degrees (pi/2 radians). That's what yaw_offset is for.

Here's where it gets used:

https://github.com/cra-ros-pkg/robot_localization/blob/0fe3097f58b4c7f7645aba20e0e675468182e707/src/navsat_transform.cpp#L286

Here's an example. In this case, we'll imagine our IMU is in Boston, MA, USA. Here's where an IMU would read 0:

image description

But we need it to be 0 when facing east. So when it's facing magnetic north, we'd want the data from it to read

pi/2 + magnetic_declination_radians

So we need to add pi/2 + magnetic_declination_radians to every IMU reading before we can use it. In other word, yaw_offset here (and in most applications) would be pi/2.

Your IMU probably reads 0 at magnetic north. But we need a heading reference that aligns with the UTM grid, where +X points east, and +Y points north. That means we need our heading from the IMU to read 0 when the robot is facing east. So we have two parameters (technically we have 3, but one, the UTM meridian convergence, is accounted for automatically in the code):

  1. If we adjust for magnetic declination (using the magnetic_declination_radians parameter), we can get the IMU data to read 0 at true north, rather than magnetic north. But that means we have a heading of 0 when we face north, but we need it to be 0 when we face east, so...
  2. ...we need to adjust for that 90 degrees (pi/2 radians). That's what yaw_offset is for.

Here's where it gets used:

https://github.com/cra-ros-pkg/robot_localization/blob/0fe3097f58b4c7f7645aba20e0e675468182e707/src/navsat_transform.cpp#L286

Here's an example. In this case, we'll imagine our IMU is in Boston, MA, USA. Here's where an IMU would read 0:

image description

But we need it to be 0 when facing east. So when it's facing magnetic north, we'd want the data from it to read

pi/2 + magnetic_declination_radians

So we need to add pi/2 + magnetic_declination_radians to every IMU reading before we can use it. In other word, words, yaw_offset here (and in most applications) would be pi/2.