-
Notifications
You must be signed in to change notification settings - Fork 904
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
Fix odometry and acceleration processing pipeline #753
Conversation
Thank you for the PR. Can you clarify some of these? Everything is marked as a fix, but these appear to be feature enhancements. Are you fixing any specific bugs that you can detail? Maybe just generally provide use cases that are solved by these changes.
I need to go over the PR, but what will happen if the odometry data is not provided in a frame relative to base_link, e.g., if it comes from a motion capture system that has a fixed transform to the robot's world frame (direct transform from mocap_frame to odom)? |
Items 1 and 2 were made in parallel with #728 , but with the additional enhancements of transforming the covariance correspondingly. To enable this feature, set parameter odomX_pose_use_child_frame to true.
Background of the fix:
A mobile robot has both a wheel odometer and an Intel RealSense T265 camera. The wheel odometer registers odom message at the geometry center of the robot (header.frame_id is odom and child_frame is base_link), while T265 reports odometry of itself -- header.frame_id is T265_odom and child_frame is T265_link. I want to fuse these two odom sources with EKF.
With the T265 mounted on the edge of the robot, which is 30cm from base_link, a simple static transform from odom to T265_odom is not enough, as the size of the robot will couple rotation into the position components. Therefore, the differences in the two odom sources needs a proper transformation of the odom headers and child frames.
Q: "what will happen if the odometry data is not provided in a frame relative to base_link, e.g., if it comes from a motion capture system that has a fixed transform to the robot's world frame (direct transform from mocap_frame to odom)?"
A: This PR, as well as #728, fixes exactly that issue. E.g. in a motion capturing system, the origin of the robot pose is not necessarily the same as the origin of the wheel odometer on the robot, and the velocity reference frames (child_link) are not necessarily the same. Assume the mocap system provides odom message describing tf: mocap_odom->mocap_frame, the pose and velocity measured by the mocap on the child link (mocap_frame) should undergo the following transformation chain:
mocap_frame->mocap_odom->odom->base_link
to obtain the pose of base_link in odom.
According to the definition of Odometry message, mocap_odom->odom is addressed by a static transform, and odom->base_link is provided by the robot odometer.
Item 3 resolves the TODO in the prepareAcceleration function. The acceleration, after transformed to base_link, needs to remove the centripetal acceleration Omega x (Omega x r), where r is the translation vector. It also needs to remove the linear acceleration due to angular acceleration, beta x r, where beta is the time differential of Omega.
Item 4 adds a flag to support removal of gravity on IMU sensors that are not mounted upright and yet reports a pose relative to its intialization pose. Examples include the IMU sensor on the Intel RealSense cameras, which reports the readings in the optical frame and with tf to base_link specified. The feature is enabled by setting the imuX_relative parameter to true.
✅TODO: I will populate comments on the changed sections and fix the linting issue.
✅TODO: A bug in the PR is found when removing gravity. I will push a follow-up commit.
…________________________________
From: Tom Moore ***@***.***>
Sent: Wednesday, May 11, 2022 4:39:31 AM
To: cra-ros-pkg/robot_localization ***@***.***>
Cc: Yang, Haoguang ***@***.***>; Author ***@***.***>
Subject: Re: [cra-ros-pkg/robot_localization] Fix odometry and acceleration processing pipeline (PR #753)
Thank you for the PR.
Can you clarify some of these? Everything is marked as a fix, but these appear to be feature enhancements. Are you fixing any specific bugs that you can detail? Maybe just generally provide use cases that are solved by these changes.
Fix odometry pose transform when odometry origin is different from base_link
I need to go over the PR, but what will happen if the odometry data is not provided in a frame relative to base_link, e.g., if it comes from a motion capture system that has a fixed transform to the robot's world frame (direct transform from mocap_frame to odom)?
―
Reply to this email directly, view it on GitHub<#753 (comment)>, or unsubscribe<https://github.com/notifications/unsubscribe-auth/ACPMIPFEE2VBAPXOFN6ZFOTVJNW4HANCNFSM5VTACTRA>.
You are receiving this because you authored the thread.Message ID: ***@***.***>
|
…atted code for linting checks.
I haven't forgotten about this. Just need to make time for review. Thanks again for the PR and details. |
Hang on, I want to back up on this point. I'm sure you are aware of all of this, but for completeness, I want to go over it here.
This has been supported from day 1; the reason I use this specific example is because I have done this exact thing. It also works if you want to fuse, e.g., Gazebo's "perfect" state messages into the robot's pose. But again, for externally-referenced world frames, this already worked. Likewise, the package makes the assumption that any velocity data will be reported in a frame that can be transformed to If a One of the main shortcomings of #728 solved this, I believe, by making it so that |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
OK, took a deeper read through this, and it looks sound. Thanks for the PR!
state(StateMemberVyaw)); | ||
angular_acceleration_ = (newStateTwistRot - lastStateTwistRot_)/dt; | ||
const Eigen::MatrixXd &cov = filter_.getEstimateErrorCovariance(); | ||
for (size_t i = 0; i < 3; i ++) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Just for consistency, it might make sense to change 3 to ORIENTATION_SIZE
.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
for (size_t i = 0; i < 3; i ++) | |
for (size_t i = 0; i < ORIENTATION_SIZE; i ++) |
I see #728 was actually broader in scope than I realised, and isn't just targeting differential mode. |
…d to ros2 rolling
state(StateMemberVyaw)); | ||
angular_acceleration_ = (newStateTwistRot - lastStateTwistRot_)/dt; | ||
const Eigen::MatrixXd &cov = filter_.getEstimateErrorCovariance(); | ||
for (size_t i = 0; i < 3; i ++) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
for (size_t i = 0; i < 3; i ++) | |
for (size_t i = 0; i < ORIENTATION_SIZE; i ++) |
const Eigen::MatrixXd &cov = filter_.getEstimateErrorCovariance(); | ||
for (size_t i = 0; i < 3; i ++) | ||
{ | ||
for (size_t j = 0; j < 3; j ++) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
for (size_t j = 0; j < 3; j ++) | |
for (size_t j = 0; j < ORIENTATION_SIZE; j ++) |
I came here because I suddenly see drift in my odometry state because my IMU is at a small but non-negligable angle (maybe the robot is at that angle, or the imu is not mounted perfectly straight. Looking at this PR, I find it odd that:
|
Fix odometry pose transform when odometry origin is different from base_link.
Fix covariance transformation when Odometry msg child_frame is not base_link.
Fix acceleration transformation, considering angular acceleration and centripetal acceleration.
Fix gravity removal for IMU with relative orientation (initial pose as [0,0,0,1]).