Browse Source

AP_MSP: added airspeed support

c415-sdk
Andrew Tridgell 4 years ago
parent
commit
ae2a310b9c
  1. 16
      libraries/AP_MSP/AP_MSP_Telem_Backend.cpp
  2. 1
      libraries/AP_MSP/AP_MSP_Telem_Backend.h

16
libraries/AP_MSP/AP_MSP_Telem_Backend.cpp

@ -15,6 +15,7 @@ @@ -15,6 +15,7 @@
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_BLHeli/AP_BLHeli.h>
#include <RC_Channel/RC_Channel.h>
@ -492,6 +493,11 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_sensor_command(uint16_t cmd_m @@ -492,6 +493,11 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_sensor_command(uint16_t cmd_m
msp_handle_baro(*pkt);
}
break;
case MSP2_SENSOR_AIRSPEED: {
const MSP::msp_airspeed_data_message_t *pkt = (const MSP::msp_airspeed_data_message_t *)src->ptr;
msp_handle_airspeed(*pkt);
}
break;
}
return MSP_RESULT_NO_REPLY;
@ -540,6 +546,16 @@ void AP_MSP_Telem_Backend::msp_handle_baro(const MSP::msp_baro_data_message_t &p @@ -540,6 +546,16 @@ void AP_MSP_Telem_Backend::msp_handle_baro(const MSP::msp_baro_data_message_t &p
#endif
}
void AP_MSP_Telem_Backend::msp_handle_airspeed(const MSP::msp_airspeed_data_message_t &pkt)
{
#if HAL_MSP_AIRSPEED_ENABLED
auto *airspeed = AP::airspeed();
if (airspeed) {
airspeed->handle_msp(pkt);
}
#endif
}
MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_raw_gps(sbuf_t *dst)
{
#if OSD_ENABLED

1
libraries/AP_MSP/AP_MSP_Telem_Backend.h

@ -164,6 +164,7 @@ protected: @@ -164,6 +164,7 @@ protected:
void msp_handle_gps(const MSP::msp_gps_data_message_t &pkt);
void msp_handle_compass(const MSP::msp_compass_data_message_t &pkt);
void msp_handle_baro(const MSP::msp_baro_data_message_t &pkt);
void msp_handle_airspeed(const MSP::msp_airspeed_data_message_t &pkt);
// implementation specific helpers
// custom masks are needed for vendor specific settings

Loading…
Cancel
Save