mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
GCS_MAVLink: move sending of POSITION_TARGET_GLOBAL_INT up
This commit is contained in:
parent
2c962afe98
commit
0ca888d52a
@ -188,6 +188,7 @@ public:
|
|||||||
void send_named_float(const char *name, float value) const;
|
void send_named_float(const char *name, float value) const;
|
||||||
void send_home() const;
|
void send_home() const;
|
||||||
void send_ekf_origin() const;
|
void send_ekf_origin() const;
|
||||||
|
virtual void send_position_target_global_int() { };
|
||||||
void send_servo_output_raw(bool hil);
|
void send_servo_output_raw(bool hil);
|
||||||
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
|
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
|
||||||
void send_accelcal_vehicle_position(uint32_t position);
|
void send_accelcal_vehicle_position(uint32_t position);
|
||||||
|
@ -2843,6 +2843,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
send_local_position();
|
send_local_position();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_POSITION_TARGET_GLOBAL_INT:
|
||||||
|
CHECK_PAYLOAD_SIZE(POSITION_TARGET_GLOBAL_INT);
|
||||||
|
send_position_target_global_int();
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_RADIO_IN:
|
case MSG_RADIO_IN:
|
||||||
CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
|
CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
|
||||||
send_radio_in();
|
send_radio_in();
|
||||||
|
Loading…
Reference in New Issue
Block a user