AP_UAVCAN: subscribe airspeed message

This commit is contained in:
liang.tang 2018-09-04 23:46:12 -07:00 committed by Andrew Tridgell
parent 653766c4cc
commit bcaa4901ed
1 changed files with 2 additions and 0 deletions

View File

@ -41,6 +41,7 @@
#include <AP_GPS/AP_GPS_UAVCAN.h>
#include <AP_BattMonitor/AP_BattMonitor_UAVCAN.h>
#include <AP_Compass/AP_Compass_UAVCAN.h>
#include <AP_Airspeed/AP_Airspeed_UAVCAN.h>
#define LED_DELAY_US 50000
@ -195,6 +196,7 @@ void AP_UAVCAN::init(uint8_t driver_index)
AP_Compass_UAVCAN::subscribe_msgs(this);
AP_Baro_UAVCAN::subscribe_msgs(this);
AP_BattMonitor_UAVCAN::subscribe_msgs(this);
AP_Airspeed_UAVCAN::subscribe_msgs(this);
act_out_array[driver_index] = new uavcan::Publisher<uavcan::equipment::actuator::ArrayCommand>(*_node);
act_out_array[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2));