ethz-asl / rovio

Other
1.12k stars 506 forks source link

World-IMU Initial TF Transform, IMU-Camera TF Transform/Extrinsics #190

Open lawchekun opened 6 years ago

lawchekun commented 6 years ago

Hi,

I have 2 questions.

1) World-IMU Initial TF transform.

When there is no initial TF transform between the the World and IMU frame specified in the rovio.info file, should the World and IMU frames be aligned (Identity transformation matrix)?

However, I am getting a difference in orientation/transform between my World and IMU frame, which I'm not sure why is this happening.

world-imu-frame 2

2) IMU-Camera TF Transform (Extrinsic Calibration in rovio.info file)

For my setup, the camera frame with respect to the IMU is an euler angle transformation of ZYX (90, 0, 90) which corresponds to (0.5, 0.5, 0.5, 0.5) in quaternion notation. This is for the extrinsic calibration parameters between IMU-Camera.

I have verified this by using http://wiki.ros.org/tf2/Tutorials/Quaternions

However, for it to work right when I visualize it in Rviz, I had to input (0.5, 0.5, 0.5, -0.5)

I noticed this when I published the /rovio/extrinsics topic, and that the sign for the w quaternion term was flipped.

I looked at the code in https://github.com/ethz-asl/rovio/blob/master/include/rovio/RovioNode.hpp

      extrinsicsMsg_[camID].pose.pose.orientation.w = -state.qCM(camID).w();

Just wondering if flipping the sign for the w in the quaternion term in the rovio.info file for the extrinsic parameters between IMU-Camera is the right approach? And why there is a need to flip the sign when publishing the extrinsic message in Rovio?

Thanks for the help!

lawchekun commented 6 years ago

Regarding

1) World-IMU Initial TF transform

Upon testing with other data, I realized that it is identity transformation.

I'm not sure why the initial pose offset for position works but not orientation (quaternion) though?

I'm rotating/offsetting my IMU frame wrt world frame by rotating it 90 degrees about the z axis. (XYZ order rotation) which corresponds to a quaternion of (0, 0, 0.7071068, 0.7071068)

In my rovio.info config file it is

Init { State { pos_0 -0.010; X-entry of initial position (world to IMU in world) [m] pos_1 -0.010; Y-entry of initial position (world to IMU in world) [m] pos_2 0.310; Z-entry of initial position (world to IMU in world) [m] vel_0 0; X-entry of initial velocity (robocentric, IMU) [m/s] vel_1 0; Y-entry of initial velocity (robocentric, IMU) [m/s] vel_2 0; Z-entry of initial velocity (robocentric, IMU) [m/s] acb_0 0; X-entry of accelerometer bias [m/s^2] acb_1 0; Y-entry of accelerometer bias [m/s^2] acb_2 0; Z-entry of accelerometer bias [m/s^2] gyb_0 0; X-entry of gyroscope bias [rad/s] gyb_1 0; Y-entry of gyroscope bias [rad/s] gyb_2 0; Z-entry of gyroscope bias [rad/s] att_x 0; X-entry of initial attitude (IMU to world, Hamilton) att_y 0; Y-entry of initial attitude (IMU to world, Hamilton) att_z 0.7071068; Z-entry of initial attitude (IMU to world, Hamilton) att_w 0.7071068; W-entry of initial attitude (IMU to world, Hamilton) }

However, I do not see the transformation when I visualize it in Rviz. Just wondering if anyone else has seen this issue?

Please advise! Thanks for the help!

bloesch commented 6 years ago
  1. Rovio requires a World frame that is aligned with gravity (along z). So if your initial camera frame does not have the z-axis pointing along the gravity, rovio will use the first accelerometer measurement in order to fix this.

  2. Rovio uses qCM, which maps from IMU frame to Camera frame. If I am not wrong the extrinsicsMsg_ is the other way round (from Camera to IMU) and thus the flip in w.

lawchekun commented 6 years ago
  1. I am abit confused by this statement, do you mean the IMU frame or camera frame? So you mean to say that it will align the the z axis of the IMU frame based on the first accelerometer measurement?

As my camera frame follows the standard convention in ROS where Z is facing forward. http://www.ros.org/reps/rep-0103.html

  1. Is it the other way round for this? It seems like for extrinsics, qCM (quaternion representing the rotation from IMU to camera in Hamilton-convention).

Based on https://github.com/ethz-asl/rovio/wiki/Configuration

bloesch commented 6 years ago

If you transform the accelerometer measurement from IMU frame to world frame it should align with the z-axis (assuming there is little motion). Meaning that if the accelerometer measurement is not aligned with the z-axis of the IMU frame at the time of initialisation we cannot initialise the orientation with identity. I can formulate it mathematically: C_WI I_g = W_g.

joesparza commented 5 years ago

Regarding

1. World-IMU Initial TF transform

Upon testing with other data, I realized that it is identity transformation.

I'm not sure why the initial pose offset for position works but not orientation (quaternion) though?

I'm rotating/offsetting my IMU frame wrt world frame by rotating it 90 degrees about the z axis. (XYZ order rotation) which corresponds to a quaternion of (0, 0, 0.7071068, 0.7071068)

In my rovio.info config file it is

Init { State { pos_0 -0.010; X-entry of initial position (world to IMU in world) [m] pos_1 -0.010; Y-entry of initial position (world to IMU in world) [m] pos_2 0.310; Z-entry of initial position (world to IMU in world) [m] vel_0 0; X-entry of initial velocity (robocentric, IMU) [m/s] vel_1 0; Y-entry of initial velocity (robocentric, IMU) [m/s] vel_2 0; Z-entry of initial velocity (robocentric, IMU) [m/s] acb_0 0; X-entry of accelerometer bias [m/s^2] acb_1 0; Y-entry of accelerometer bias [m/s^2] acb_2 0; Z-entry of accelerometer bias [m/s^2] gyb_0 0; X-entry of gyroscope bias [rad/s] gyb_1 0; Y-entry of gyroscope bias [rad/s] gyb_2 0; Z-entry of gyroscope bias [rad/s] att_x 0; X-entry of initial attitude (IMU to world, Hamilton) att_y 0; Y-entry of initial attitude (IMU to world, Hamilton) att_z 0.7071068; Z-entry of initial attitude (IMU to world, Hamilton) att_w 0.7071068; W-entry of initial attitude (IMU to world, Hamilton) }

However, I do not see the transformation when I visualize it in Rviz. Just wondering if anyone else has seen this issue?

Please advise! Thanks for the help!

I have exactly the same case, @lawchekun . Were you able to rotate the IMU frame through the z-axis, and visualize it in Rviz? Thanks in advance!

escobarhector commented 2 years ago

I am having the same issue. What we realized is that if we initialize our system upside down then we can see that IMU and World frame align every time. But if we initialize it facing down, then we get a different transformation every time.