Configuring robot_localization
Integration with robot_localization is straightforward at this point. Simply add this block to your state estimation node launch file:
<param name="odomN" value="/your_state_estimation_node_topic">
<rosparam param="odomN_config">[true, true, false,
false, false, false,
false, false, false,
false, false, false,
false, false, false]</rosparam>
<param name="odomN_differential" value="false"/>
Make sure to change odomN to whatever your odometry input values is (e.g., odom1, odom2, etc.). Also, if you wish to include altitude data, set odomN_config‘s third value to true.
Note
If you are operating in 2D don’t have any sensor measuring Z or Z velocity, you can either:
- Set navsat_transform_node's zero_altitude parameter to true, and then set odomN_config‘s third value to true
- Set two_d_mode to true in your robot_localization state estimation node
You should have no need to modify the _differential setting within the state estimation node. The GPS is an absolute position sensor, and enabling differential integration defeats the purpose of using it.
Details
We’ll start with a picture. Consider a robot that starts at some latitude and longitude and with some heading. We assume in this tutorial that the heading comes from an IMU that reads 0 when facing east, and increases according to the ROS spec (i.e., counter-clockwise). The remainder of this tutorial will refer to Figure 1:
REP-105 suggests four coordinate frames: base_link, odom, map, and earth. base_link is the coordinate frame that is rigidly attached to the vehicle. The odom and map frames are world-fixed frames and generally have their origins at the vehicle’s start position and orientation. The earth frame is used as a common reference frame for multiple map frames, and is not yet supported by navsat_transform_node. Note that in Figure 1, the robot has just started (t = 0), and so its base_link, odom, and map frames are aligned. We can also define a coordinate frame for the UTM grid, which we will call utm. For the purposes of this tutorial, we will refer to the UTM grid coordinate frame as utm. Therefore, what we want to do is create a utm->*map* transform.
Referring to Figure 1, these ideas are (hopefully) made clear. The UTM origin is the \((0_{UTM}, 0_{UTM})\) point of the UTM zone that is associated with the robot’s GPS location. The robot begins somewhere within the UTM zone at location \((x_{UTM}, y_{UTM})\). The robot’s initial orientation is some angle \(\theta\) above the UTM grid’s \(X\)-axis. Our transform will therefore require that we know \(x_{UTM}, y_{UTM}\) and \(\theta\).
We now need to convert our latitude and longitude to UTM coordinates. The UTM grid assumes that the \(X\)-axis faces east, the \(Y\)-axis faces (true) north, and the \(Z\)-axis points up out of the ground. This complies with the right-handed coordinate frame as dictated by REP-105. The REP also states that a yaw angle of \(0\) means that we are facing straight down the \(X\)-axis, and that the yaw increases counter-clockwise. navsat_transform_node assumes your heading data conforms to this standard. However, there are two factors that need to be considered:
- The IMU driver may not allow the user to apply the magnetic declination correction factor
- The IMU driver may incorrectly report \(0\) when facing north, and not when facing east (even though its headings increase and decrease correctly). Fortunately, navsat_transform_node exposes two parameters to adddress these possible shortcomings in IMU data: magnetic_declination_radians and yaw_offset. Referring to Figure 1, for an IMU that is currently measuring a yaw value of imu_yaw,
\(yaw_{imu} = -\omega - offset_{yaw} + \theta\)
\(\theta = yaw_{imu} + \omega + offset_{yaw}\)
We now have a translation \((x_{UTM}, y_{UTM})\) and rotation \(\theta\), which we can use to create the required utm -> map transform. We use the transform to convert all future GPS positions into the robot’s local coordinate frame. navsat_transform_node will also broadcast this transform if the broadcast_utm_transform parameter is set to true.
If you have any questions about this tutorial, please feel free to ask questions on answers.ros.org.