|
|
|
@ -48,6 +48,9 @@ void AP_Periph_FW::msp_sensor_update(void)
@@ -48,6 +48,9 @@ void AP_Periph_FW::msp_sensor_update(void)
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_MAG |
|
|
|
|
send_msp_compass(); |
|
|
|
|
#endif |
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_AIRSPEED |
|
|
|
|
send_msp_airspeed(); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -160,4 +163,33 @@ void AP_Periph_FW::send_msp_compass(void)
@@ -160,4 +163,33 @@ void AP_Periph_FW::send_msp_compass(void)
|
|
|
|
|
} |
|
|
|
|
#endif // HAL_PERIPH_ENABLE_MAG
|
|
|
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_AIRSPEED |
|
|
|
|
/*
|
|
|
|
|
send MSP airspeed packet |
|
|
|
|
*/ |
|
|
|
|
void AP_Periph_FW::send_msp_airspeed(void) |
|
|
|
|
{ |
|
|
|
|
MSP::msp_airspeed_data_message_t p; |
|
|
|
|
|
|
|
|
|
const uint32_t last_update_ms = airspeed.last_update_ms(); |
|
|
|
|
if (msp.last_airspeed_ms == last_update_ms) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
msp.last_airspeed_ms = last_update_ms; |
|
|
|
|
|
|
|
|
|
p.instance = 0; |
|
|
|
|
p.time_ms = msp.last_airspeed_ms; |
|
|
|
|
p.pressure = airspeed.get_corrected_pressure(); |
|
|
|
|
float temp; |
|
|
|
|
if (!airspeed.get_temperature(temp)) { |
|
|
|
|
p.temp = INT16_MIN; //invalid temperature
|
|
|
|
|
} else { |
|
|
|
|
p.temp = temp * 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
send_msp_packet(MSP2_SENSOR_AIRSPEED, &p, sizeof(p)); |
|
|
|
|
} |
|
|
|
|
#endif // HAL_PERIPH_ENABLE_AIRSPEED
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#endif // HAL_PERIPH_ENABLE_MSP
|
|
|
|
|