Skip to content

Commit 0122854

Browse files
chobitsfanpeterbarker
authored andcommitted
GCS_MAVLink: fix odometry pos, ang err calculation
1 parent ab0bd00 commit 0122854

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4061,8 +4061,8 @@ void GCS_MAVLINK::handle_odometry(const mavlink_message_t &msg)
40614061
float posErr = 0;
40624062
float angErr = 0;
40634063
if (!isnan(m.pose_covariance[0])) {
4064-
posErr = cbrtf(sq(m.pose_covariance[0])+sq(m.pose_covariance[6])+sq(m.pose_covariance[11]));
4065-
angErr = cbrtf(sq(m.pose_covariance[15])+sq(m.pose_covariance[18])+sq(m.pose_covariance[20]));
4064+
posErr = sqrtf(m.pose_covariance[0]+m.pose_covariance[6]+m.pose_covariance[11]);
4065+
angErr = sqrtf(m.pose_covariance[15]+m.pose_covariance[18]+m.pose_covariance[20]);
40664066
}
40674067

40684068
const uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(m.time_usec, PAYLOAD_SIZE(chan, ODOMETRY));
@@ -4099,8 +4099,8 @@ void GCS_MAVLINK::handle_common_vision_position_estimate_data(const uint64_t use
40994099
}
41004100

41014101
if (!isnan(covariance[0])) {
4102-
posErr = cbrtf(sq(covariance[0])+sq(covariance[6])+sq(covariance[11]));
4103-
angErr = cbrtf(sq(covariance[15])+sq(covariance[18])+sq(covariance[20]));
4102+
posErr = sqrtf(covariance[0]+covariance[6]+covariance[11]);
4103+
angErr = sqrtf(covariance[15]+covariance[18]+covariance[20]);
41044104
}
41054105

41064106
visual_odom->handle_pose_estimate(usec, timestamp_ms, x, y, z, roll, pitch, yaw, posErr, angErr, reset_counter, 0);

0 commit comments

Comments
 (0)