GCS_MAVLink: move sending of POSITION_TARGET_GLOBAL_INT up

This commit is contained in:
Peter Barker 2018-05-11 21:54:48 +10:00 committed by Peter Barker
parent 2c962afe98
commit 0ca888d52a
2 changed files with 6 additions and 0 deletions

View File

@ -188,6 +188,7 @@ public:
void send_named_float(const char *name, float value) const;
void send_home() const;
void send_ekf_origin() const;
virtual void send_position_target_global_int() { };
void send_servo_output_raw(bool hil);
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
void send_accelcal_vehicle_position(uint32_t position);

View File

@ -2843,6 +2843,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_local_position();
break;
case MSG_POSITION_TARGET_GLOBAL_INT:
CHECK_PAYLOAD_SIZE(POSITION_TARGET_GLOBAL_INT);
send_position_target_global_int();
break;
case MSG_RADIO_IN:
CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
send_radio_in();