mirror of https://github.com/ArduPilot/ardupilot
Copter: rename send_extended_status1 to send_sys_status
This commit is contained in:
parent
703eef7fb4
commit
75fb9780f7
|
@ -728,7 +728,7 @@ private:
|
||||||
// GCS_Mavlink.cpp
|
// GCS_Mavlink.cpp
|
||||||
void gcs_send_heartbeat(void);
|
void gcs_send_heartbeat(void);
|
||||||
void send_fence_status(mavlink_channel_t chan);
|
void send_fence_status(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);
|
||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
|
|
||||||
|
|
|
@ -126,7 +126,7 @@ NOINLINE void Copter::send_fence_status(mavlink_channel_t chan)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
NOINLINE void Copter::send_sys_status(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
int16_t battery_current = -1;
|
int16_t battery_current = -1;
|
||||||
int8_t battery_remaining = -1;
|
int8_t battery_remaining = -1;
|
||||||
|
@ -278,7 +278,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
||||||
// to avoid unnecessary errors being reported to user
|
// to avoid unnecessary errors being reported to user
|
||||||
if (copter.ap.initialised) {
|
if (copter.ap.initialised) {
|
||||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
||||||
copter.send_extended_status1(chan);
|
copter.send_sys_status(chan);
|
||||||
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
||||||
send_power_status();
|
send_power_status();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue