AP_Periph: enable airspeed sensor

This commit is contained in:
Andrew Tridgell 2019-10-03 21:02:56 +10:00
parent 36d62367cb
commit e07a6b63b1
6 changed files with 83 additions and 0 deletions

View File

@ -79,6 +79,10 @@ void AP_Periph_FW::init()
adsb_init(); adsb_init();
#endif #endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
airspeed.init();
#endif
start_ms = AP_HAL::millis(); start_ms = AP_HAL::millis();
} }

View File

@ -3,6 +3,7 @@
#include <AP_GPS/AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_Compass/AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Baro/AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_Airspeed/AP_Airspeed.h>
#if defined(HAL_PERIPH_NEOPIXEL_COUNT) || defined(HAL_PERIPH_ENABLE_NCP5623_LED) #if defined(HAL_PERIPH_NEOPIXEL_COUNT) || defined(HAL_PERIPH_ENABLE_NCP5623_LED)
#define AP_PERIPH_HAVE_LED #define AP_PERIPH_HAVE_LED
@ -24,6 +25,7 @@ public:
void can_mag_update(); void can_mag_update();
void can_gps_update(); void can_gps_update();
void can_baro_update(); void can_baro_update();
void can_airspeed_update();
void load_parameters(); void load_parameters();
@ -51,6 +53,10 @@ public:
} adsb; } adsb;
#endif #endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
AP_Airspeed airspeed;
#endif
// setup the var_info table // setup the var_info table
AP_Param param_loader{var_info}; AP_Param param_loader{var_info};
@ -59,6 +65,7 @@ public:
uint32_t last_mag_update_ms; uint32_t last_mag_update_ms;
uint32_t last_gps_update_ms; uint32_t last_gps_update_ms;
uint32_t last_baro_update_ms; uint32_t last_baro_update_ms;
uint32_t last_airspeed_update_ms;
}; };
extern AP_Periph_FW periph; extern AP_Periph_FW periph;

View File

@ -58,6 +58,13 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GSCALAR(led_brightness, "LED_BRIGHTNESS", AP_PERIPH_LED_BRIGHT_DEFAULT), GSCALAR(led_brightness, "LED_BRIGHTNESS", AP_PERIPH_LED_BRIGHT_DEFAULT),
#endif #endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
// Airspeed driver
// @Group: ARSP
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
GOBJECT(airspeed, "ARSP", AP_Airspeed),
#endif
AP_VAREND AP_VAREND
}; };

View File

@ -19,6 +19,7 @@ public:
k_param_baro, k_param_baro,
k_param_buzz_volume, k_param_buzz_volume,
k_param_led_brightness, k_param_led_brightness,
k_param_airspeed,
}; };
AP_Int16 format_version; AP_Int16 format_version;

View File

@ -32,6 +32,7 @@
#include <uavcan/equipment/gnss/Auxiliary.h> #include <uavcan/equipment/gnss/Auxiliary.h>
#include <uavcan/equipment/air_data/StaticPressure.h> #include <uavcan/equipment/air_data/StaticPressure.h>
#include <uavcan/equipment/air_data/StaticTemperature.h> #include <uavcan/equipment/air_data/StaticTemperature.h>
#include <uavcan/equipment/air_data/RawAirData.h>
#include <uavcan/equipment/indication/BeepCommand.h> #include <uavcan/equipment/indication/BeepCommand.h>
#include <uavcan/equipment/indication/LightsCommand.h> #include <uavcan/equipment/indication/LightsCommand.h>
#include <ardupilot/indication/SafetyState.h> #include <ardupilot/indication/SafetyState.h>
@ -261,6 +262,9 @@ static void handle_param_executeopcode(CanardInstance* ins, CanardRxTransfer* tr
#endif #endif
#ifdef HAL_PERIPH_ENABLE_BARO #ifdef HAL_PERIPH_ENABLE_BARO
AP_Param::setup_object_defaults(&periph.baro, periph.baro.var_info); AP_Param::setup_object_defaults(&periph.baro, periph.baro.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
AP_Param::setup_object_defaults(&periph.airspeed, periph.airspeed.var_info);
#endif #endif
} }
@ -894,6 +898,7 @@ void AP_Periph_FW::can_update()
can_mag_update(); can_mag_update();
can_gps_update(); can_gps_update();
can_baro_update(); can_baro_update();
can_airspeed_update();
#ifdef HAL_PERIPH_ENABLE_BUZZER #ifdef HAL_PERIPH_ENABLE_BUZZER
can_buzzer_update(); can_buzzer_update();
#endif #endif
@ -1125,6 +1130,64 @@ void AP_Periph_FW::can_baro_update(void)
#endif // HAL_PERIPH_ENABLE_BARO #endif // HAL_PERIPH_ENABLE_BARO
} }
/*
update CAN airspeed
*/
void AP_Periph_FW::can_airspeed_update(void)
{
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
if (!airspeed.healthy()) {
static uint32_t last_probe_ms;
uint32_t now = AP_HAL::millis();
if (now - last_probe_ms >= 1000) {
last_probe_ms = now;
airspeed.init();
}
}
airspeed.update(false);
if (last_airspeed_update_ms == airspeed.last_update_ms()) {
return;
}
last_airspeed_update_ms = airspeed.last_update_ms();
if (!airspeed.healthy()) {
// don't send any data
return;
}
const float press = airspeed.get_differential_pressure();
float temp;
if (!airspeed.get_temperature(temp)) {
temp = nanf("");
} else {
temp += C_TO_KELVIN;
}
uavcan_equipment_air_data_RawAirData pkt {};
pkt.differential_pressure = press;
pkt.static_air_temperature = temp;
fix_float16(pkt.differential_pressure);
fix_float16(pkt.static_air_temperature);
// unfilled elements are NaN
pkt.static_pressure = nanf("");
pkt.static_pressure_sensor_temperature = nanf("");
pkt.differential_pressure_sensor_temperature = nanf("");
pkt.pitot_temperature = nanf("");
uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_MAX_SIZE];
uint16_t total_size = uavcan_equipment_air_data_RawAirData_encode(&pkt, buffer);
canardBroadcast(&canard,
UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_SIGNATURE,
UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_ID,
&transfer_id,
CANARD_TRANSFER_PRIORITY_LOW,
&buffer[0],
total_size);
#endif // HAL_PERIPH_ENABLE_AIRSPEED
}
#ifdef HAL_PERIPH_ENABLE_ADSB #ifdef HAL_PERIPH_ENABLE_ADSB
/* /*
map an ADSB_VEHICLE MAVLink message to a UAVCAN TrafficReport message map an ADSB_VEHICLE MAVLink message to a UAVCAN TrafficReport message

View File

@ -32,6 +32,7 @@ def build(bld):
'Filter', 'Filter',
'AP_InternalError', 'AP_InternalError',
'GCS_MAVLink', 'GCS_MAVLink',
'AP_Airspeed',
], ],
exclude_src=[ exclude_src=[
'libraries/AP_HAL_ChibiOS/Storage.cpp' 'libraries/AP_HAL_ChibiOS/Storage.cpp'