Skip to content

Commit

Permalink
AP_DroneCAN: call RPM subscribe
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Mar 14, 2024
1 parent 6b0529c commit 1447876
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions libraries/AP_DroneCAN/AP_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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);
Expand Down

0 comments on commit 1447876

Please sign in to comment.