mirror of https://github.com/ArduPilot/ardupilot
AP_DroneCAN: call RPM subscribe
This commit is contained in:
parent
dff29a5015
commit
982cc3a00f
|
@ -61,6 +61,8 @@
|
|||
|
||||
#include <AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.h>
|
||||
|
||||
#include <AP_RPM/RPM_DroneCAN.h>
|
||||
|
||||
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);
|
||||
|
|
Loading…
Reference in New Issue