From 2443341d0427103014a9cc2424e340dd6624c316 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 14 Mar 2024 00:59:02 +0000 Subject: [PATCH] AP_DroneCAN: call RPM subscribe --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index b72899bf72cae9..67c629b2416168 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -61,6 +61,8 @@ #include +#include + extern const AP_HAL::HAL& hal; // setup default pool size @@ -396,6 +398,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) #if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED AP_TemperatureSensor_DroneCAN::subscribe_msgs(this); #endif +#if AP_RPM_DRONECAN_ENABLED + AP_RPM_DroneCAN::subscribe_msgs(this); +#endif act_out_array.set_timeout_ms(5); act_out_array.set_priority(CANARD_TRANSFER_PRIORITY_HIGH);