diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 548cb706e2..dc3d16ab7e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3381,7 +3381,9 @@ 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); - const Vector3f vel{m.vx, m.vy, m.vz}; + // convert velocity vector from FRD to NED frame + Vector3f vel{m.vx, m.vy, m.vz}; + vel = q * vel; visual_odom->handle_vision_speed_estimate(m.time_usec, timestamp_ms, vel, m.reset_counter); #endif }