From 92927cd8482b27975bc72e0eaed57d0c72170833 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 10 May 2018 16:56:25 +1000 Subject: [PATCH] GCS_MAVLink: move try_send_message of servo-output-raw up --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 9 +++++++-- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index d669c25d50..13a179fcc5 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -189,7 +189,7 @@ public: void send_home() 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(); static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour); void send_accelcal_vehicle_position(uint32_t position); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c432b1c4db..8bc43e4994 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1652,10 +1652,10 @@ bool GCS_MAVLINK::telemetry_delayed() const /* send SERVO_OUTPUT_RAW */ -void GCS_MAVLINK::send_servo_output_raw(bool hil) +void GCS_MAVLINK::send_servo_output_raw() { uint16_t values[16] {}; - if (hil) { + if (in_hil_mode()) { for (uint8_t i=0; i<16; i++) { values[i] = SRV_Channels::srv_channel(i)->get_output_pwm(); } @@ -2868,6 +2868,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_sensor_offsets(); break; + case MSG_SERVO_OUTPUT_RAW: + CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); + send_servo_output_raw(); + break; + case MSG_AHRS: CHECK_PAYLOAD_SIZE(AHRS); send_ahrs();