mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Sub: move sending of fence_status message up
This commit is contained in:
parent
1412921561
commit
05c9ded9fc
@ -428,13 +428,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
|||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_FENCE_STATUS:
|
|
||||||
#if AC_FENCE == ENABLED
|
|
||||||
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
|
|
||||||
sub.fence_send_mavlink_status(chan);
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_PID_TUNING:
|
case MSG_PID_TUNING:
|
||||||
CHECK_PAYLOAD_SIZE(PID_TUNING);
|
CHECK_PAYLOAD_SIZE(PID_TUNING);
|
||||||
sub.send_pid_tuning(chan);
|
sub.send_pid_tuning(chan);
|
||||||
|
@ -579,7 +579,6 @@ private:
|
|||||||
void mainloop_failsafe_enable();
|
void mainloop_failsafe_enable();
|
||||||
void mainloop_failsafe_disable();
|
void mainloop_failsafe_disable();
|
||||||
void fence_check();
|
void fence_check();
|
||||||
void fence_send_mavlink_status(mavlink_channel_t chan);
|
|
||||||
bool set_mode(control_mode_t mode, mode_reason_t reason);
|
bool set_mode(control_mode_t mode, mode_reason_t reason);
|
||||||
void update_flight_mode();
|
void update_flight_mode();
|
||||||
void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
|
void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
|
||||||
|
@ -49,27 +49,4 @@ void Sub::fence_check()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// fence_send_mavlink_status - send fence status to ground station
|
|
||||||
void Sub::fence_send_mavlink_status(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
if (fence.enabled()) {
|
|
||||||
// traslate fence library breach types to mavlink breach types
|
|
||||||
uint8_t mavlink_breach_type = FENCE_BREACH_NONE;
|
|
||||||
uint8_t breaches = fence.get_breaches();
|
|
||||||
if ((breaches & AC_FENCE_TYPE_ALT_MAX) != 0) {
|
|
||||||
mavlink_breach_type = FENCE_BREACH_MAXALT;
|
|
||||||
}
|
|
||||||
if ((breaches & AC_FENCE_TYPE_CIRCLE) != 0) {
|
|
||||||
mavlink_breach_type = FENCE_BREACH_BOUNDARY;
|
|
||||||
}
|
|
||||||
|
|
||||||
// send status
|
|
||||||
mavlink_msg_fence_status_send(chan,
|
|
||||||
(int8_t)(fence.get_breaches()!=0),
|
|
||||||
fence.get_breach_count(),
|
|
||||||
mavlink_breach_type,
|
|
||||||
fence.get_breach_time());
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user