mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: vicon send odometry with quality of 50
This commit is contained in:
parent
b03b1c856d
commit
94150368ee
@ -233,7 +233,8 @@ void Vicon::update_vicon_position_estimate(const Location &loc,
|
|||||||
MAV_FRAME_LOCAL_FRD,
|
MAV_FRAME_LOCAL_FRD,
|
||||||
MAV_FRAME_BODY_FRD,
|
MAV_FRAME_BODY_FRD,
|
||||||
0,
|
0,
|
||||||
MAV_ESTIMATOR_TYPE_VIO
|
MAV_ESTIMATOR_TYPE_VIO,
|
||||||
|
50 // quality hardcoded to 50%
|
||||||
};
|
};
|
||||||
mavlink_msg_odometry_encode_status(
|
mavlink_msg_odometry_encode_status(
|
||||||
system_id,
|
system_id,
|
||||||
|
Loading…
Reference in New Issue
Block a user