Browse Source

Plane: rename send_extended_status1 to send_sys_status

master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
d1727d26a1
  1. 4
      ArduPlane/GCS_Mavlink.cpp
  2. 2
      ArduPlane/Plane.h

4
ArduPlane/GCS_Mavlink.cpp

@ -152,7 +152,7 @@ void Plane::send_fence_status(mavlink_channel_t chan) @@ -152,7 +152,7 @@ void Plane::send_fence_status(mavlink_channel_t chan)
#endif
void Plane::send_extended_status1(mavlink_channel_t chan)
void Plane::send_sys_status(mavlink_channel_t chan)
{
int16_t battery_current = -1;
int8_t battery_remaining = -1;
@ -435,7 +435,7 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) @@ -435,7 +435,7 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS);
plane.send_extended_status1(chan);
plane.send_sys_status(chan);
CHECK_PAYLOAD_SIZE2(POWER_STATUS);
send_power_status();
break;

2
ArduPlane/Plane.h

@ -800,7 +800,7 @@ private: @@ -800,7 +800,7 @@ private:
void update_load_factor(void);
void send_fence_status(mavlink_channel_t chan);
void update_sensor_status_flags(void);
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_servo_out(mavlink_channel_t chan);
void send_wind(mavlink_channel_t chan);

Loading…
Cancel
Save