robot_pose_ekf, microstrain_3dmgx2_imu, and UTM coordinates
I am using a P3DX with a Garmin GPS and a 3DMGX2 IMU. I am trying to use the robot_pose_ekf to fuse the P3DX's internal odometry with the GPS data and the IMU data. I have successfully named and remapped the required topics to get them to all act as input to robot_pose_ekf (vo is the GPS UTM coordinates). However, when I look at the data, it's clear to me that I am missing some transformations. I lack the karma and webspace required to show images, so I'll have to give as much detail as I can when asking my questions:
(1) First, the IMU. I have named my IMU's coordinate frame imu. I have defined a static transform from base_link to imu that currently has only a Z-offset. I believe I have the IMU oriented correctly; the connector faces forward when mounted on the robot. The image on the ROS 3DMGX2 node's page (http://www.ros.org/wiki/microstrain_3dmgx2_imu) has an image with what appears to be the coordinate frame that is assumed by the unit. However, the authors point out that "The orientation is produced by the IMU firmware, which uses gravity, and in some cases the Earth's magnetic field, to remove integration drift. The orientation matrix is the transpose of the orientation matrix returned by the hardware, rotated 180 degrees around the y axis. This corresponds to a transformation from the IMU frame to the world frame, with the z axis point up." As I understand it, the data coming from the microstraing_3dmgx2_imu node is in line with the ROS right-handed coordinate frame specification. Is this correct? If anyone else has used this particular sensor with robot_pose_ekf, did you need to apply any additional transformations before passing the data into robot_pose_ekf?
(2) The UTM coordinates produced by the GPS are, of course, not in the assumed ROS frame. The filter is currently doing this:
my_filter_.addMeasurement(StampedTransform(vo_meas_.inverse(), vo_stamp_, "base_footprint", "vo"), vo_covariance_);
Would it be sufficient to provide a transformation for base_footprint to vo that would convert from UTM frame (+x to the right, +y up) to the ROS specification (+x up, +y to the left)?
(3) Do any transformations need to be applied to the P3DX's odometry before passing it into the filter? It appears as if it treats +x as forward and +y as left, so I think it ought to be usable as-is.
My tf tree has odom_combined->base_footprint (provided by the EKF node), base_footprint->base_link (static, currently all 0s), and base_link->imu (all 0s except the Z-offset).
I have tried running the filter with only P3DX odometry + IMU, and the results look worse than the odometry by itself, and do not at all reflect the robot's true path.
I have tried running it with just UTM + IMU, and the results look worse than UTM by itself.
If anyone has any insight, I'd appreciate it. I realize it's not much to go ...