Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

A question about function imuConverter() #264

Closed
Psyclonus2887 opened this issue Jun 30, 2021 · 4 comments
Closed

A question about function imuConverter() #264

Psyclonus2887 opened this issue Jun 30, 2021 · 4 comments
Labels

Comments

@Psyclonus2887
Copy link

First thank you for your excellent work! I apply LIO_SAM in our data set constructed by Hesai lidar and OxT GNSS system, and it performs well. But I have a question when reading the code.
In utility.h, the imuConverter() function is aimed to convert acc, gyr and RPY gained in IMU frame into lidar frame, in my opinion. But if so, RPY in lidar frame should be calculated by:
q_final = extQRPY * q_from * extQRPY_inv
Is there something wrong in this calculiation?

@Psyclonus2887
Copy link
Author

I refer to that because in one of my cars, the rotation matrix from lidar frame to imu frame is [0, -1, 0, -1, 0, 0, 0, 0, -1], but the transformed RPY is really strange.

@stale
Copy link

stale bot commented Jul 14, 2021

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

@stale stale bot added the stale label Jul 14, 2021
@stale stale bot closed this as completed Jul 20, 2021
@narutojxl
Copy link

narutojxl commented Nov 16, 2021

Hi all, i think maybe it should be q_from * extQRPY_inv in imuConverter(), there are my reasons about how i think, if you have any idea, hope to discuss together to make this clearly, thanks a again.

  • We suppose imu is not installed horizontally on the robot, in other word, the imu's orientation quat has a roll≠0, pitch≠0 at first readings. If the imu is a 6 axis imu, its first data's orientation has yaw = 0. If it is a 9 axis imu, its first data's orientation maybe has yaw ≠0 depending on earth's magnetic field . IMU's world frame is a horizontally frame(roll and pitch are all zero) regardless of it is a 6 axis imu or 9.

  • IMU: orientation: https://www.ros.org/reps/rep-0145.html

If an orientation estimate is provided (see Data Reporting), the device world frame represents the external reference with respect to which the sensor frame is indicated. Two out of three degrees of freedom of the sensor frame w.r.t. the world frame are usually considered "fixed" through gravity, with the relevant conventions from REP 103 [1] :
For NED type IMUs, the orientation of the world frame is x-north, y-east, z-down, relative to magnetic north.
For ENU type IMUs, the orientation of the world frame is x-east, y-north, z-up, relative to magnetic north.
If the device does not have an absolute yaw reference (magnetometer), the world frame will only be aligned in roll and pitch (due to gravity), while the orientation around the z axis can be arbitrary.
  • According to issues/6, if imu's acc axis(+x, +y, +z) align with gyro axis(+x, +y, +z) for each them, extrinsicRot and extrinsicRPY are the same, which is from laser frame to imu frame extrinsic rot, transforms a point from imu's frame into laser's frame.
  • We also suppose laser is not installed horizontally on the robot, its extrinsic rot between imu is got from extrinsicRot or extrinsicRPY. q_from * extQRPY_inv is laser frame in imu's world frame. Multiply left with extQRPY , that is to say extQRPY*q_from * extQRPY_inv does not make sense, because extQRPY is laser to imu, not laser to imu's world frame.
  • In updateInitialGuess() of mapOptmization.cpp when cloudKeyPoses3D->points.empty() ==true, transformTobeMapped[0]= cloudInfo.imuRollInit;, transformTobeMapped[1] = cloudInfo.imuPitchInit;, then in addOdomFactor() add transformTobeMapped[] as the origin node, namely map frame. So the map frame's position is the position of first laser received, its attitude is roll = 0, pitch =0, and yaw whether equal zero depends on it is a 6 axis imu , 9 axis imu and useImuHeadingInitialization flag.

@hanhaoguang
Copy link

  • ptmization.cpp when

I agree with you. I think it should be q_final = q_from * extQRPY_inv

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

3 participants