mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_DroneCAN: add subscribe msgs for TemperatureSensor
This commit is contained in:
parent
26bfedb956
commit
5fd3be1b75
@ -59,6 +59,8 @@
|
|||||||
#include <AP_Relay/AP_Relay.h>
|
#include <AP_Relay/AP_Relay.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include <AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
// setup default pool size
|
// setup default pool size
|
||||||
@ -391,6 +393,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
|
|||||||
#if HAL_MOUNT_XACTI_ENABLED
|
#if HAL_MOUNT_XACTI_ENABLED
|
||||||
AP_Mount_Xacti::subscribe_msgs(this);
|
AP_Mount_Xacti::subscribe_msgs(this);
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED
|
||||||
|
AP_TemperatureSensor_DroneCAN::subscribe_msgs(this);
|
||||||
|
#endif
|
||||||
|
|
||||||
act_out_array.set_timeout_ms(5);
|
act_out_array.set_timeout_ms(5);
|
||||||
act_out_array.set_priority(CANARD_TRANSFER_PRIORITY_HIGH);
|
act_out_array.set_priority(CANARD_TRANSFER_PRIORITY_HIGH);
|
||||||
|
Loading…
Reference in New Issue
Block a user