diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 844d2d5c08..0e92dc1177 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -2548,13 +2548,23 @@ protected: if (_mavlink->odometry_loopback_enabled()) { odom_updated = _vodom_sub.update(&odom); - msg.frame_id = MAV_FRAME_LOCAL_NED; + + // set the frame_id according to the local frame of the data + if (odom.local_frame == vehicle_odometry_s::LOCAL_FRAME_NED) { + msg.frame_id = MAV_FRAME_LOCAL_NED; + + } else { + msg.frame_id = MAV_FRAME_LOCAL_FRD; + } + // source: external vision system msg.estimator_type = MAV_ESTIMATOR_TYPE_VISION; } else { odom_updated = _odom_sub.update(&odom); + msg.frame_id = MAV_FRAME_LOCAL_NED; + // source: PX4 estimator msg.estimator_type = MAV_ESTIMATOR_TYPE_AUTOPILOT; } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index e14839b98f..5e42484ec7 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1309,8 +1309,6 @@ MavlinkReceiver::handle_message_odometry(mavlink_message_t *msg) q_body_to_local.normalize(); q_body_to_local.copyTo(odometry.q); - odometry.local_frame = vehicle_odometry_s::LOCAL_FRAME_FRD; - // pose_covariance static constexpr size_t POS_URT_SIZE = sizeof(odometry.pose_covariance) / sizeof(odometry.pose_covariance[0]); static_assert(POS_URT_SIZE == (sizeof(odom.pose_covariance) / sizeof(odom.pose_covariance[0])), @@ -1361,6 +1359,14 @@ MavlinkReceiver::handle_message_odometry(mavlink_message_t *msg) * with true North */ if (odom.frame_id == MAV_FRAME_LOCAL_NED || odom.frame_id == MAV_FRAME_LOCAL_FRD) { + + if (odom.frame_id == MAV_FRAME_LOCAL_NED) { + odometry.local_frame = vehicle_odometry_s::LOCAL_FRAME_NED; + + } else { + odometry.local_frame = vehicle_odometry_s::LOCAL_FRAME_FRD; + } + if (odom.estimator_type == MAV_ESTIMATOR_TYPE_VISION || odom.estimator_type == MAV_ESTIMATOR_TYPE_VIO) { _visual_odometry_pub.publish(odometry); diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 3de3928023..47ed1f5dbc 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -1037,7 +1037,12 @@ int Simulator::publish_odometry_topic(const mavlink_message_t *odom_mavlink) matrix::Quatf q(odom_msg.q[0], odom_msg.q[1], odom_msg.q[2], odom_msg.q[3]); q.copyTo(odom.q); - odom.local_frame = vehicle_odometry_s::LOCAL_FRAME_FRD; + if (odom_msg.frame_id == MAV_FRAME_LOCAL_NED) { + odom.local_frame = vehicle_odometry_s::LOCAL_FRAME_NED; + + } else { + odom.local_frame = vehicle_odometry_s::LOCAL_FRAME_FRD; + } static_assert(POS_URT_SIZE == (sizeof(odom_msg.pose_covariance) / sizeof(odom_msg.pose_covariance[0])), "Odometry Pose Covariance matrix URT array size mismatch");