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

msg/vehicle_odometry.msg: simplify covariance handling and update all usage #19966

Merged
merged 5 commits into from
Aug 4, 2022

Conversation

dagar
Copy link
Member

@dagar dagar commented Jul 26, 2022

  • replace float32[21] URT covariances with smaller dedicated position/velocity/orientation covariances
  • these are easier to casually inspect and more representative of what's actually being used currently and reduces the size of vehicle_odometry_s quite a bit
  • ekf2: add new helper to get roll/pitch/yaw covariances
  • mavlink: delete unused ATT_POS_MOCAP stream (this is just a passthrough)
  • mavlink: ODOMETRY receiver
    • handle trivial frame conversions in place (MAV_FRAME_LOCAL_ENU, MAV_FRAME_LOCAL_FLU, etc)
    • ODOMETRY velocity support more than just MAV_FRAME_BODY_FRD
pxh> listener vehicle_odometry

TOPIC: vehicle_odometry
 vehicle_odometry
    timestamp: 45748000 (0.004000 seconds ago)
    timestamp_sample: 45748000 (0 us before timestamp)
    position: [2.0012, -0.0012, 0.4814]
    q: [0.7066, 0.0020, -0.0115, 0.7075] (Roll: -0.8 deg, Pitch: -1.1 deg, Yaw: 90.1 deg)
    position_covariance: [0.0000, -0.0000, 0.0000, 0.0000, 0.0000, 0.0162]
    orientation_covariance: [0.0007, 0.0004, -0.0000, 0.0004, -0.0000, 0.0000]
    velocity: [0.0030, -0.0008, -0.0006]
    angular_velocity: [-0.0004, 0.0026, -0.0027]
    velocity_covariance: [0.0000, -0.0000, -0.0000, 0.0000, -0.0000, 0.0000]
    local_frame: 1
    velocity_frame: 1
    reset_counter: 6
    quality: 0

PR is stacked on top of #19965.

@dagar dagar requested a review from bresch July 26, 2022 15:54
@dagar dagar force-pushed the pr-odometry_msg_cleanup branch from fa31f4b to 3f423dc Compare July 26, 2022 15:57
@dagar dagar requested a review from mhkabir July 26, 2022 15:58
@dagar dagar force-pushed the pr-odometry_msg_cleanup branch 4 times, most recently from 9591bb1 to 4a9c846 Compare July 26, 2022 17:00
msg/vehicle_odometry.msg Outdated Show resolved Hide resolved
msg/vehicle_odometry.msg Outdated Show resolved Hide resolved
msg/vehicle_odometry.msg Outdated Show resolved Hide resolved
msg/vehicle_odometry.msg Outdated Show resolved Hide resolved
msg/vehicle_odometry.msg Outdated Show resolved Hide resolved
uint8 POSITION_COVARIANCE_Y_VAR = 3
uint8 POSITION_COVARIANCE_YZ_COV = 4
uint8 POSITION_COVARIANCE_Z_VAR = 5
float32[6] position_covariance
Copy link
Member

@mhkabir mhkabir Jul 26, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I propose dropping all crossterms and only keeping the variances for each direct measurement (pos, orientation, vel). I'm yet to come across any real system where the crossterms are used/useful.

For real systems, generating actually correct (co)variance estimates is also really challenging in the first place

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@james-modalai any opinion?

@dagar
Copy link
Member Author

dagar commented Jul 26, 2022

Covariances dropped as suggested, but it's in a separate commit we can revert if someone disagrees.

float32 rollspeed # Angular velocity about X body axis
float32 pitchspeed # Angular velocity about Y body axis
float32 yawspeed # Angular velocity about Z body axis
float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is probably unnecessary?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Perhaps mildly useful for comparison, but otherwise we're not even using it.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Most systems don't even estimate that in my experience, hence suggestion to drop

@dagar dagar force-pushed the pr-ekf2_aux_aid_src_status branch 3 times, most recently from c45c681 to 305d1d1 Compare July 29, 2022 15:22
Base automatically changed from pr-ekf2_aux_aid_src_status to main July 29, 2022 16:02
dagar added 2 commits July 29, 2022 12:04
… usage

 - replace float32[21] URT covariances with smaller dedicated
position/velocity/orientation covariances
 - these are easier to casually inspect and more representative of
what's actually being used currently and reduces the size of
vehicle_odometry_s quite a bit
 - ekf2: add new helper to get roll/pitch/yaw covariances
 - mavlink: delete unused ATT_POS_MOCAP stream (this is just a passthrough)
@dagar dagar force-pushed the pr-odometry_msg_cleanup branch from dfe38af to 4e80750 Compare July 29, 2022 16:39
@dagar dagar requested a review from james-modalai July 30, 2022 15:58
@dagar dagar force-pushed the pr-odometry_msg_cleanup branch from 3b27f8a to 2110da5 Compare August 4, 2022 14:08
src/modules/mavlink/mavlink_receiver.cpp Outdated Show resolved Hide resolved
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
@dagar dagar merged commit dfdfbbf into main Aug 4, 2022
@dagar dagar deleted the pr-odometry_msg_cleanup branch August 4, 2022 16:55
@dagar dagar mentioned this pull request Aug 4, 2022
6 tasks
@mengchaoheng
Copy link

mengchaoheng commented Jul 24, 2024

why NaN is better than 0 ? @dagar

for (auto &pc : msg.pose_covariance) {
  pc = NAN;
}

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

Successfully merging this pull request may close these issues.

4 participants