Browse Source

Sub: Use named float wrappers

master
Michael du Breuil 7 years ago committed by Francisco Ferreira
parent
commit
2d7f60ab59
  1. 65
      ArduSub/GCS_Mavlink.cpp
  2. 2
      ArduSub/GCS_Mavlink.h
  3. 1
      ArduSub/Sub.h

65
ArduSub/GCS_Mavlink.cpp

@ -364,58 +364,35 @@ void NOINLINE Sub::send_temperature(mavlink_channel_t chan) @@ -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) @@ -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:

2
ArduSub/GCS_Mavlink.h

@ -35,6 +35,8 @@ private: @@ -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;

1
ArduSub/Sub.h

@ -487,7 +487,6 @@ private: @@ -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);

Loading…
Cancel
Save