diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.cpp b/libraries/AP_UAVCAN/AP_UAVCAN.cpp index da429fd672..ea9f1b06e6 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN.cpp @@ -580,7 +580,7 @@ void AP_UAVCAN::SRV_push_servos() for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) { // Check if this channels has any function assigned - if (SRV_Channels::channel_function(i) > SRV_Channel::k_none) { + if (SRV_Channels::channel_function(i) >= SRV_Channel::k_none) { _SRV_conf[i].pulse = SRV_Channels::srv_channel(i)->get_output_pwm(); _SRV_conf[i].esc_pending = true; _SRV_conf[i].servo_pending = true; diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.h b/libraries/AP_UAVCAN/AP_UAVCAN.h index 7048225fbe..15f9d6c2ea 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.h +++ b/libraries/AP_UAVCAN/AP_UAVCAN.h @@ -31,11 +31,11 @@ #include #include #include - +#include #ifndef UAVCAN_SRV_NUMBER -#define UAVCAN_SRV_NUMBER 18 +#define UAVCAN_SRV_NUMBER NUM_SERVO_CHANNELS #endif #define AP_UAVCAN_SW_VERS_MAJOR 1