mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavlink: odometry: Initialize the covariance matrix to 0 to prevent the entire matrix from becoming invalid after mavros performs coordinate transformation. (#26321)
This commit is contained in:
parent
e2864e521f
commit
1cfab8feb2
@ -112,7 +112,7 @@ private:
|
||||
// Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle
|
||||
// (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.)
|
||||
for (auto &pc : msg.pose_covariance) {
|
||||
pc = NAN;
|
||||
pc = 0.f;
|
||||
}
|
||||
|
||||
msg.pose_covariance[0] = odom.position_variance[0]; // X row 0, col 0
|
||||
@ -127,7 +127,7 @@ private:
|
||||
// Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle
|
||||
// (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.)
|
||||
for (auto &vc : msg.velocity_covariance) {
|
||||
vc = NAN;
|
||||
vc = 0.f;
|
||||
}
|
||||
|
||||
msg.velocity_covariance[0] = odom.velocity_variance[0]; // X row 0, col 0
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user