AP_Periph: add AP_RPM support

Co-authored-by: Samuel Tabor <samuel.tabor@krausaerospace.com>
This commit is contained in:
Tom Pittenger 2023-08-02 14:34:40 -07:00 committed by Tom Pittenger
parent 0de754bff3
commit 1a67775c52
5 changed files with 25 additions and 0 deletions

View File

@ -269,6 +269,10 @@ void AP_Periph_FW::init()
nmea.init();
#endif
#ifdef HAL_PERIPH_ENABLE_RPM
rpm_sensor.init();
#endif
#ifdef HAL_PERIPH_ENABLE_NOTIFY
notify.init();
#endif
@ -474,6 +478,13 @@ void AP_Periph_FW::update()
temperature_sensor.update();
#endif
#ifdef HAL_PERIPH_ENABLE_RPM
if (now - rpm_last_update_ms >= 100) {
rpm_last_update_ms = now;
rpm_sensor.update();
}
#endif
#if HAL_LOGGING_ENABLED
logger.periodic_tasks();
#endif

View File

@ -26,6 +26,7 @@
#include <AP_HAL/CANIface.h>
#include <AP_Stats/AP_Stats.h>
#include <AP_Networking/AP_Networking.h>
#include <AP_RPM/AP_RPM.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_ESC_Telem/AP_ESC_Telem_config.h>
#if HAL_WITH_ESC_TELEM
@ -159,6 +160,11 @@ public:
AP_Baro baro;
#endif
#ifdef HAL_PERIPH_ENABLE_RPM
AP_RPM rpm_sensor;
uint32_t rpm_last_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_BATTERY
struct AP_Periph_Battery {
void handle_battery_failsafe(const char* type_str, const int8_t action) { }

View File

@ -557,6 +557,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(networking, "NET_", AP_Networking),
#endif
#ifdef HAL_PERIPH_ENABLE_RPM
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT(rpm_sensor, "RPM", AP_RPM),
#endif
AP_VAREND
};

View File

@ -77,6 +77,7 @@ public:
k_param_pole_count1,
k_param_esc_serial_port1,
k_param_networking,
k_param_rpm_sensor,
};
AP_Int16 format_version;

View File

@ -70,6 +70,7 @@ def build(bld):
'AP_Stats',
'AP_EFI',
'AP_CheckFirmware',
'AP_RPM',
'AP_Proximity',
]
bld.ap_stlib(