Skip to content

Commit

Permalink
GCS_MAVLink: add support for AIRSPEED message
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Sep 16, 2024
1 parent c3393d8 commit 8318109
Show file tree
Hide file tree
Showing 3 changed files with 70 additions and 0 deletions.
7 changes: 7 additions & 0 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <AP_Winch/AP_Winch_config.h>
#include <AP_AHRS/AP_AHRS_config.h>
#include <AP_Arming/AP_Arming_config.h>
#include <AP_Airspeed/AP_Airspeed_config.h>

#include "ap_message.h"

Expand Down Expand Up @@ -360,6 +361,12 @@ class GCS_MAVLINK
void send_scaled_pressure();
void send_scaled_pressure2();
virtual void send_scaled_pressure3(); // allow sub to override this
#if AP_AIRSPEED_ENABLED
// Send per instance airspeed message
// last index is used to rotate through sensors
void send_airspeed();
uint8_t last_airspeed_idx;
#endif
void send_simstate() const;
void send_sim_state() const;
void send_ahrs();
Expand Down
62 changes: 62 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1125,6 +1125,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
#endif
#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
{ MAVLINK_MSG_ID_RELAY_STATUS, MSG_RELAY_STATUS},
#endif
#if AP_AIRSPEED_ENABLED
{ MAVLINK_MSG_ID_AIRSPEED, MSG_AIRSPEED},
#endif
};

Expand Down Expand Up @@ -2327,6 +2330,58 @@ void GCS_MAVLINK::send_scaled_pressure3()
send_scaled_pressure_instance(2, mavlink_msg_scaled_pressure3_send);
}

#if AP_AIRSPEED_ENABLED
void GCS_MAVLINK::send_airspeed()
{
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
if (airspeed == nullptr) {
return;
}

for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
// Try and send the next sensor
const uint8_t index = (last_airspeed_idx + 1 + i) % AIRSPEED_MAX_SENSORS;
if (!airspeed->enabled(index)) {
continue;
}

float temperature_float;
int16_t temperature = INT16_MAX;
if (airspeed->get_temperature(index, temperature_float)) {
temperature = int16_t(temperature_float * 100);
}

uint8_t flags = 0;
// Set unhealthy flag
if (!airspeed->healthy(index)) {
flags |= 1U << AIRSPEED_SENSOR_FLAGS::AIRSPEED_SENSOR_UNHEALTHY;
}

// Set using flag if the AHRS is using this sensor
const AP_AHRS &ahrs = AP::ahrs();
if (ahrs.using_airspeed_sensor() && (ahrs.get_active_airspeed_index() == index)) {
flags |= 1U << AIRSPEED_SENSOR_FLAGS::AIRSPEED_SENSOR_USING;
}

// Assemble message and send
const mavlink_airspeed_t msg {
airspeed : airspeed->get_airspeed(index),
raw_press : airspeed->get_differential_pressure(index),
temperature : temperature,
id : index,
flags : flags
};

mavlink_msg_airspeed_send_struct(chan, &msg);

// Only send one msg per call
last_airspeed_idx = index;
return;
}

}
#endif

#if AP_AHRS_ENABLED
void GCS_MAVLINK::send_ahrs()
{
Expand Down Expand Up @@ -6288,6 +6343,13 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_scaled_pressure3();
break;

#if AP_AIRSPEED_ENABLED
case MSG_AIRSPEED:
CHECK_PAYLOAD_SIZE(AIRSPEED);
send_airspeed();
break;
#endif

case MSG_SERVO_OUTPUT_RAW:
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
send_servo_output_raw();
Expand Down
1 change: 1 addition & 0 deletions libraries/GCS_MAVLink/ap_message.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,5 +100,6 @@ enum ap_message : uint8_t {
#if AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED
MSG_HIGHRES_IMU,
#endif
MSG_AIRSPEED,
MSG_LAST // MSG_LAST must be the last entry in this enum
};

0 comments on commit 8318109

Please sign in to comment.