mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
ArduCopter: include precision landing sensor in mavlink system status
Set MAV_SYS_STATUS_SENSOR_VISION_POSITION bit in onboard_control_sensors_present, onboard_control_sensors_enabled and onboard_control_sensors_health based on the status of precision landing sensor.
This commit is contained in:
parent
25de3c74c5
commit
3751dbef91
@ -143,6 +143,11 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
|||||||
if (optflow.enabled()) {
|
if (optflow.enabled()) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#if PRECISION_LANDING == ENABLED
|
||||||
|
if (precland.enabled()) {
|
||||||
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
if (ap.rc_receiver_present) {
|
if (ap.rc_receiver_present) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||||
@ -194,6 +199,11 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
|||||||
if (optflow.healthy()) {
|
if (optflow.healthy()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#if PRECISION_LANDING == ENABLED
|
||||||
|
if (precland.healthy()) {
|
||||||
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
if (ap.rc_receiver_present && !failsafe.radio) {
|
if (ap.rc_receiver_present && !failsafe.radio) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||||
|
Loading…
Reference in New Issue
Block a user