GCS_MAVLink: move try_send_message of servo-output-raw up

This commit is contained in:
Peter Barker 2018-05-10 16:56:25 +10:00 committed by Francisco Ferreira
parent 2112d76b75
commit 92927cd848
2 changed files with 8 additions and 3 deletions

View File

@ -189,7 +189,7 @@ public:
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() { }; 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); 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);

View File

@ -1652,10 +1652,10 @@ bool GCS_MAVLINK::telemetry_delayed() const
/* /*
send SERVO_OUTPUT_RAW send SERVO_OUTPUT_RAW
*/ */
void GCS_MAVLINK::send_servo_output_raw(bool hil) void GCS_MAVLINK::send_servo_output_raw()
{ {
uint16_t values[16] {}; uint16_t values[16] {};
if (hil) { if (in_hil_mode()) {
for (uint8_t i=0; i<16; i++) { for (uint8_t i=0; i<16; i++) {
values[i] = SRV_Channels::srv_channel(i)->get_output_pwm(); 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(); send_sensor_offsets();
break; break;
case MSG_SERVO_OUTPUT_RAW:
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
send_servo_output_raw();
break;
case MSG_AHRS: case MSG_AHRS:
CHECK_PAYLOAD_SIZE(AHRS); CHECK_PAYLOAD_SIZE(AHRS);
send_ahrs(); send_ahrs();