mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Sub: rename send_extended_status1 to send_sys_status
This commit is contained in:
parent
d1727d26a1
commit
e2e17b8822
@ -84,7 +84,7 @@ MAV_STATE GCS_MAVLINK_Sub::system_status() const
|
|||||||
return MAV_STATE_STANDBY;
|
return MAV_STATE_STANDBY;
|
||||||
}
|
}
|
||||||
|
|
||||||
NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
|
NOINLINE void Sub::send_sys_status(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
uint32_t control_sensors_present;
|
uint32_t control_sensors_present;
|
||||||
uint32_t control_sensors_enabled;
|
uint32_t control_sensors_enabled;
|
||||||
@ -404,7 +404,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
|||||||
// to avoid unnecessary errors being reported to user
|
// to avoid unnecessary errors being reported to user
|
||||||
if (sub.ap.initialised) {
|
if (sub.ap.initialised) {
|
||||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
||||||
sub.send_extended_status1(chan);
|
sub.send_sys_status(chan);
|
||||||
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
||||||
send_power_status();
|
send_power_status();
|
||||||
}
|
}
|
||||||
|
@ -475,7 +475,7 @@ private:
|
|||||||
void rotate_body_frame_to_NE(float &x, float &y);
|
void rotate_body_frame_to_NE(float &x, float &y);
|
||||||
void gcs_send_heartbeat(void);
|
void gcs_send_heartbeat(void);
|
||||||
void send_heartbeat(mavlink_channel_t chan);
|
void send_heartbeat(mavlink_channel_t chan);
|
||||||
void send_extended_status1(mavlink_channel_t chan);
|
void send_sys_status(mavlink_channel_t chan);
|
||||||
void send_nav_controller_output(mavlink_channel_t chan);
|
void send_nav_controller_output(mavlink_channel_t chan);
|
||||||
#if RPM_ENABLED == ENABLED
|
#if RPM_ENABLED == ENABLED
|
||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
|
Loading…
Reference in New Issue
Block a user