GCS_MAVLink: Use renamed visual odom function

* Now called pose instead of position

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2023-08-07 19:35:14 -06:00 committed by Randy Mackay
parent 1615038e57
commit 578ba20df0

View File

@ -3570,7 +3570,7 @@ void GCS_MAVLINK::handle_odometry(const mavlink_message_t &msg)
}
const uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(m.time_usec, PAYLOAD_SIZE(chan, ODOMETRY));
visual_odom->handle_vision_position_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, q, posErr, angErr, m.reset_counter);
visual_odom->handle_pose_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, q, posErr, angErr, m.reset_counter);
// convert velocity vector from FRD to NED frame
Vector3f vel{m.vx, m.vy, m.vz};
@ -3607,7 +3607,7 @@ void GCS_MAVLINK::handle_common_vision_position_estimate_data(const uint64_t use
angErr = cbrtf(sq(covariance[15])+sq(covariance[18])+sq(covariance[20]));
}
visual_odom->handle_vision_position_estimate(usec, timestamp_ms, x, y, z, roll, pitch, yaw, posErr, angErr, reset_counter);
visual_odom->handle_pose_estimate(usec, timestamp_ms, x, y, z, roll, pitch, yaw, posErr, angErr, reset_counter);
}
void GCS_MAVLINK::handle_att_pos_mocap(const mavlink_message_t &msg)
@ -3623,7 +3623,7 @@ void GCS_MAVLINK::handle_att_pos_mocap(const mavlink_message_t &msg)
return;
}
// note: att_pos_mocap does not include reset counter
visual_odom->handle_vision_position_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, m.q, 0, 0, 0);
visual_odom->handle_pose_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, m.q, 0, 0, 0);
}
void GCS_MAVLINK::handle_vision_speed_estimate(const mavlink_message_t &msg)