Skip to content

Commit 776d378

Browse files
author
alireza787b
committed
mocap: wire up reset_counter, estimator_type, quality from proto fields
Replace hardcoded values with the corresponding proto fields added in mavlink/MAVSDK-Proto#395: - send_vision_position_estimate: use reset_counter field instead of hardcoded 0 (resolves the FIXME comment) - send_odometry: use reset_counter, estimator_type, quality fields instead of hardcoded 0/MAV_ESTIMATOR_TYPE_MOCAP/0 Also fixes frame_id mapping: the proto MavFrame enum uses values that don't match MAVLink (0 instead of 14 for MOCAP_NED), so add a switch to map to correct MAVLink MAV_FRAME values. For backward compatibility, estimator_type defaults to MAV_ESTIMATOR_TYPE_MOCAP when set to UNKNOWN.
1 parent d42e9f2 commit 776d378

File tree

1 file changed

+25
-5
lines changed

1 file changed

+25
-5
lines changed

src/mavsdk/plugins/mocap/mocap_impl.cpp

Lines changed: 25 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -103,7 +103,7 @@ Mocap::Result MocapImpl::send_vision_position_estimate(
103103
vision_position_estimate.angle_body.pitch_rad,
104104
vision_position_estimate.angle_body.yaw_rad,
105105
covariance.data(),
106-
0); // FIXME: reset_counter not set
106+
vision_position_estimate.reset_counter);
107107

108108
return _system_impl->send_message(message) ? Mocap::Result::Success :
109109
Mocap::Result::ConnectionError;
@@ -216,12 +216,32 @@ Mocap::Result MocapImpl::send_odometry(const Mocap::Odometry& odometry)
216216
return Mocap::Result::InvalidRequestData;
217217
}
218218

219+
// Map proto MavFrame enum to MAVLink frame value.
220+
uint8_t mav_frame;
221+
switch (odometry.frame_id) {
222+
case Mocap::Odometry::MavFrame::MocapNed:
223+
mav_frame = MAV_FRAME_MOCAP_NED;
224+
break;
225+
case Mocap::Odometry::MavFrame::LocalFrd:
226+
mav_frame = MAV_FRAME_LOCAL_FRD;
227+
break;
228+
default:
229+
mav_frame = MAV_FRAME_MOCAP_NED;
230+
break;
231+
}
232+
233+
// Default to MOCAP estimator type for backward compatibility when not set.
234+
const auto mav_estimator_type =
235+
odometry.estimator_type == Mocap::Odometry::MavEstimatorType::Unknown ?
236+
MAV_ESTIMATOR_TYPE_MOCAP :
237+
static_cast<uint8_t>(odometry.estimator_type);
238+
219239
mavlink_msg_odometry_pack(
220240
_system_impl->get_own_system_id(),
221241
_system_impl->get_own_component_id(),
222242
&message,
223243
autopilot_time_usec,
224-
static_cast<uint8_t>(odometry.frame_id),
244+
mav_frame,
225245
static_cast<uint8_t>(MAV_FRAME_BODY_FRD),
226246
odometry.position_body.x_m,
227247
odometry.position_body.y_m,
@@ -235,9 +255,9 @@ Mocap::Result MocapImpl::send_odometry(const Mocap::Odometry& odometry)
235255
odometry.angular_velocity_body.yaw_rad_s,
236256
pose_covariance.data(),
237257
velocity_covariance.data(),
238-
0,
239-
MAV_ESTIMATOR_TYPE_MOCAP,
240-
0);
258+
odometry.reset_counter,
259+
mav_estimator_type,
260+
static_cast<int8_t>(odometry.quality));
241261

242262
return _system_impl->send_message(message) ? Mocap::Result::Success :
243263
Mocap::Result::ConnectionError;

0 commit comments

Comments
 (0)