From 2d7f60ab599c9226f4e8b45f3847c12a932c98b2 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 15 May 2018 23:49:23 -0700 Subject: [PATCH] Sub: Use named float wrappers --- ArduSub/GCS_Mavlink.cpp | 65 +++++++++++++---------------------------- ArduSub/GCS_Mavlink.h | 2 ++ ArduSub/Sub.h | 1 - 3 files changed, 23 insertions(+), 45 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 351cfc5034..9190d61350 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -364,58 +364,35 @@ void NOINLINE Sub::send_temperature(mavlink_channel_t chan) celsius.temperature() * 100); } -bool NOINLINE Sub::send_info(mavlink_channel_t chan) +bool GCS_MAVLINK_Sub::send_info() { // Just do this all at once, hopefully the hard-wire telemetry requirement means this is ok // Name is char[10] - CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT); - mavlink_msg_named_value_float_send( - chan, - AP_HAL::millis(), - "CamTilt", - 1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f)); + CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT); + send_named_float("CamTilt", + 1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f)); - CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT); - mavlink_msg_named_value_float_send( - chan, - AP_HAL::millis(), - "CamPan", - 1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f)); + CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT); + send_named_float("CamPan", + 1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f)); - CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT); - mavlink_msg_named_value_float_send( - chan, - AP_HAL::millis(), - "TetherTrn", - quarter_turn_count/4); + CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT); + send_named_float("TetherTrn", + sub.quarter_turn_count/4); - CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT); - mavlink_msg_named_value_float_send( - chan, - AP_HAL::millis(), - "Lights1", - SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f); + CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT); + send_named_float("Lights1", + SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f); - CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT); - mavlink_msg_named_value_float_send( - chan, - AP_HAL::millis(), - "Lights2", - SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f); + CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT); + send_named_float("Lights2", + SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f); - CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT); - mavlink_msg_named_value_float_send( - chan, - AP_HAL::millis(), - "PilotGain", - gain); + CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT); + send_named_float("PilotGain", sub.gain); - CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT); - mavlink_msg_named_value_float_send( - chan, - AP_HAL::millis(), - "InputHold", - input_hold_engaged); + CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT); + send_named_float("InputHold", sub.input_hold_engaged); return true; } @@ -503,7 +480,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) switch (id) { case MSG_NAMED_FLOAT: - sub.send_info(chan); + send_info(); break; case MSG_EXTENDED_STATUS1: diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 88af049a23..6db0042df1 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -35,6 +35,8 @@ private: void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; bool try_send_message(enum ap_message id) override; + bool send_info(void); + MAV_TYPE frame_type() const override; MAV_MODE base_mode() const override; uint32_t custom_mode() const override; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index c527f34cf7..96070134c2 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -487,7 +487,6 @@ private: void rpm_update(); #endif void send_temperature(mavlink_channel_t chan); - bool send_info(mavlink_channel_t chan); void send_pid_tuning(mavlink_channel_t chan); void gcs_data_stream_send(void); void gcs_check_input(void);