mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Sub: eliminate MSG_LIMITS_STATUS
This commit is contained in:
parent
de7a8e20e2
commit
f0dd90b81a
@ -89,14 +89,6 @@ MAV_STATE GCS_MAVLINK_Sub::system_status() const
|
|||||||
return MAV_STATE_STANDBY;
|
return MAV_STATE_STANDBY;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AC_FENCE == ENABLED
|
|
||||||
NOINLINE void Sub::send_limits_status(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
fence_send_mavlink_status(chan);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
|
NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
uint32_t control_sensors_present;
|
uint32_t control_sensors_present;
|
||||||
@ -462,10 +454,10 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
|||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_LIMITS_STATUS:
|
case MSG_FENCE_STATUS:
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
CHECK_PAYLOAD_SIZE(LIMITS_STATUS);
|
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
|
||||||
sub.send_limits_status(chan);
|
sub.fence_send_mavlink_status(chan);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -606,7 +598,7 @@ static const uint8_t STREAM_EXTENDED_STATUS_msgs[] = {
|
|||||||
MSG_GPS2_RAW,
|
MSG_GPS2_RAW,
|
||||||
MSG_GPS2_RTK,
|
MSG_GPS2_RTK,
|
||||||
MSG_NAV_CONTROLLER_OUTPUT,
|
MSG_NAV_CONTROLLER_OUTPUT,
|
||||||
MSG_LIMITS_STATUS,
|
MSG_FENCE_STATUS,
|
||||||
MSG_NAMED_FLOAT
|
MSG_NAMED_FLOAT
|
||||||
};
|
};
|
||||||
static const uint8_t STREAM_POSITION_msgs[] = {
|
static const uint8_t STREAM_POSITION_msgs[] = {
|
||||||
|
@ -474,7 +474,6 @@ private:
|
|||||||
void gcs_send_heartbeat(void);
|
void gcs_send_heartbeat(void);
|
||||||
void gcs_send_deferred(void);
|
void gcs_send_deferred(void);
|
||||||
void send_heartbeat(mavlink_channel_t chan);
|
void send_heartbeat(mavlink_channel_t chan);
|
||||||
void send_limits_status(mavlink_channel_t chan);
|
|
||||||
void send_extended_status1(mavlink_channel_t chan);
|
void send_extended_status1(mavlink_channel_t chan);
|
||||||
void send_nav_controller_output(mavlink_channel_t chan);
|
void send_nav_controller_output(mavlink_channel_t chan);
|
||||||
void send_simstate(mavlink_channel_t chan);
|
void send_simstate(mavlink_channel_t chan);
|
||||||
|
Loading…
Reference in New Issue
Block a user