microstrain IMU in PR2
Hello,
Can anyone tell me in which orientation (where the sensor's x,y,z directions are) the microstrain IMU is attached to PR2?
The reason I am asking this because, I am little confused with transforming the data coming from the IMU.
i) In http://www.ros.org/wiki/microstrain_3dmgx2_imu it says that "The orientation matrix is the transpose of the orientation matrix returned by the hardware, rotated 180 degrees around the y axis." and I could find this in the code:
tf::Quaternion quat;
(tf::Matrix3x3(-1,0,0,
0,1,0,
0,0,-1)*
tf::Matrix3x3(orientation[0], orientation[3], orientation[6],
orientation[1], orientation[4], orientation[7],
orientation[2], orientation[5], orientation[8])).getRotation(quat);
tf::quaternionTFToMsg(quat, data.orientation);
- I actually don't quite get the logic behind this. I just feel North-East-Down (NED) convention can be converted East-North-Up (ENU) convention by just rotating PI around X axis.
ii) In the PR2 URDF I see
<!-- imu -->
<xacro:microstrain_3dmgx2_imu_v0 name="imu" parent="${name}" imu_topic="torso_lift_imu/data" update_rate="100.0" stdev="0.00017" >
<origin xyz="-0.02977 -0.1497 0.164" rpy="0 ${M_PI} 0" />
</xacro:microstrain_3dmgx2_imu_v0>
- the reason for rpy="0 ${M_PI} 0" will be clear if I know the actual IMU orientation in PR2
Thank you