gps/imu message does not adhere to REP 105
MCFurry opened this issue · 15 comments
Although I'm impressed by the oem7 capabilities and that of the ROS driver, the reported imu message of my SMART7-S receiver does not seem to adhere to REP-105 which is a pain to successfully use this message in the rest of the ROS framework.
My receiver is mounted as per manual: cable-side towards back of the vehicle. Although my roll/pitch/yaw-axis are now indeed aligned to my base_link-frame's rpy-axis, the yaw value is 0 when facing North, not when facing East (REP-105 defines ENU).
Furthermore, as per Novatel-manual, the vehicle axis of the receiver are:
- y forward
- x right
- z up
Which also seems to be the case for the 'raw' angular-rate and acceleration values, although I would expect them to adhere to REP-105 as well and thus:
- x forward
- y left
- z up
Example of oem7-imu (/gps/imu) compared to a REP-105 compliant imu (/imu/data) on the same vehicle:
Angular rate
(where clearly: /imu/data/angular_velocity/x=/gps/imu/angular_velocity/y and /imu/data/angular_velocity/y = - /gps/imu/angular_velocity/x):
Acceleration values:
(less clear, but also: /imu/data/linear_acceleration/x=/gps/imu/linear_acceleration/y and /imu/data/linear_acceleration/y = - /gps/imu/linear_acceleration/x):
Orientation:
(where yaw is North-referenced, hence /imu/data/orientation/yaw_deg = /gps/imu/orientation/yaw_deg + 90.0)
I understand that Novatel is free to chose their own 'vehicle-axis' for their sensor internally, which is fine. But since this is a ROS driver, it would be great if the messages outputted also adhere to REP's.
Thank you for bringing this REP-105 coordinate convention to our attention. Since our products serve such a wide range of applications with their own various coordinate frame standards, and the NovAtel SPAN INS output frame is historically well-defined at this point, we cannot change the default output frame. However, there is already a mechanism in place to remedy this using the "USER" parameter of the SETINSROTATION command.
For example, to rotate all INS log output from the SPAN default frame (x-right, y-forward, z-up) to your frame of choice (x-forward, y-left, z-up), you would use the command as follows: "SETINSROTATION USER 0 0 90". Note that uncertainty values are not required when using the USER parameter.
This command should be added to the std_init_commands.yaml file alongside the other INS Setup Commands.
Best regards,
NovAtel Application Engineering
Thank you for your swift response!
I understand that you serve a wide range of applications and have therefore a well-defined 'Novatel-definition'. The option to configure the INS rotation sounds useful, I'll try to test that asap!
However:
- Will this only affect accelero and gyro outputs of the IMU message, or also roll, pitch values?
- Is this setting persistent during powercycles of the SMART7S?
- If I'm understanding this correctly, than the yaw will still be North-referenced though? Would it be possible to change this in the ROS-driver?
Hi @MCFurry, to answer your questions:
- Using SETINSROTATION USER will only affect the output of OEM7 INS messages: INSPVA, INSPOS, INSVEL, INSATT, and INSSPD. In the context of the novatel_oem7_driver, that means all values in the corresponding supported topics inspva, inspvax, or any INS messages included by the user in oem7raw.
- Every time the novatel_oem7_driver is started, it will use the std_init_commands.yaml file to configure the receiver properly. If you want to have the receiver settings persist regardless of whether or not it is being used with ROS, you need to send a SAVECONFIG command.
- The definition of angle measurements such as Yaw cannot be changed. For example, in the corrimu topic, yaw rate will always be a right-handed rotation around the z-axis; in the inspva and inspvax topics, azimuth will always be in the Local-Level Frame (ENU) i.e. the left-handed rotation around the z-axis in degrees clockwise from North.
Thanks again for the response.
Your suggestions are clear, so adding the SETINSROTATION USER to the init commands will solve most of the issues, only the Yaw will then remain North referenced.
IMHO it would be good though, since this is a ROS driver, to adhere to REP 105.
Hence:
- Adding the correct SETINSROTATION USER to the std_init_commands.yaml
- Subtracting 90 degrees from the Yaw angle in the imu message
Would be two minor changes to this repo, that won't affect other usages of the receiver but does adhere to REP 105 and therefore cause less confusion to other ROS users of novatel receivers?
Would you mind fixing this? Or do you accept a PR on this?
Thank you @MCFurry for your input. We have a new feature request for this logged internally based on your feedback. I cannot comment at this time if we will implement these changes as the driver default, but it will be discussed and considered. We will leave this issue status as "open" for the time being.
Other users who want to see the default output support REP 105 as discussed, please thumbs-up the original question above to help us weigh the level of interest in this feature request.
Hi thanks for a great ROS driver. I agree with @MCFurry as a ROS driver it would be nice to have REP105 out of the box or even as an option as part of the driver. I am rolling with the SETINSROTATION USER
as suggested. Do you have an elegant way to do the subtracting 90 degrees?
My current attempt using topic_tools
:
rosrun topic_tools transform /imu /imu_corrected sensor_msgs/Imu 'sensor_msgs.msg.Imu(orientation=geometry_msgs.msg.Quaternion(tf.transformations.quaternion_multiply([m.orientation.x, m.orientation.y, m.orientation.z, m.orientation.w], tf.transformations.quaternion_about_axis(math.radians(-90), (0, 0, 1))), header=m.header, orientation_covariance=m.orientation_covariance, angular_velocity=m.angular_velocity, angular_velocity_covariance=m.angular_velocity_covariance, linear_acceleration=m.linear_acceleration, linear_acceleration_covariance=m.linear_acceleration_covariance)' --import math geometry_msgs sensor_msgs tf
Also does it make sense to rotate all the other vectors in the IMU message?
@garyedwards My apologies for the delay in response. You are correct in using the SETINSROTATION USER command to rotate to the proper frame, however we don't have the ability to adjust the azimuth output the final 90 degrees. We have commands such as HEADINGOFFSET that adjusts the GNSS heading in this manner, but nothing for the INS azimuth which I believe to be required for the REP 105 frame.
I noticed that some work apparently was done on fixing this issue?
That's great news! Is there any plan on releasing an update such that we can test this?
Hi thanks for the feedback and initial code. Is there an option for the IMU to also show the acceleration due to gravity if supported on the hardware? This is required by some SLAM algorithms.
See REP 145:
When the device is at rest, the vector will represent the specific force solely due to gravity. I.e. if the body z axis points upwards, its z axis should indicate +g. This data must be in m/s^2.
Hi thanks for the feedback and initial code. Is there an option for the IMU to also show the acceleration due to gravity if supported on the hardware? This is required by some SLAM algorithms.
See REP 145:
When the device is at rest, the vector will represent the specific force solely due to gravity. I.e. if the body z axis points upwards, its z axis should indicate +g. This data must be in m/s^2.
Ahh good addition. Robot_localization has an option for IMUs with gravity compensated z-axis. But other packages might not indeed...
@garyedwards Thank you for the feedback! This will be passed along to our development team as an improvement to be made for subsequent releases.
As the ros driver stands right now, is the /gps/imu orientation the x right, y forward, z up vehicle frame with respect to x east, y north, z up? Such that if the vehicle were facing north on level ground, the orientation would be identity?
Hi @edwardribbit , that is correct. Although this thread is a request to orient the receiver according to REP105 which is x forward,
y left, z up.
So this seems to be the highest-voted issue. Is there perhaps any timeline already?
Hi @Timple , we had implemented this fix around June-July 2021 timeframe to the main ROS1 build. I apologize if this wasn't communicated. Further communication regarding this fix will be directed to you and your organization. If you find any issues with this implementation, please let us know! Again, apologies for not communicating this update here.