diff --git a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp index 5fb5b6c69a..e0084e4798 100644 --- a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp +++ b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp @@ -9,6 +9,9 @@ #include "AP_Volz_Protocol.h" #if NUM_SERVO_CHANNELS + +#include + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Volz_Protocol::var_info[] = { diff --git a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h index c654ff4fb7..adbf5edf13 100644 --- a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h +++ b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.h @@ -34,11 +34,8 @@ #pragma once #include -#include #include -//#include - #define VOLZ_SCALE_VALUE (uint16_t)(VOLZ_EXTENDED_POSITION_MAX - VOLZ_EXTENDED_POSITION_MIN) // Extended Position Data Format defines 100 as 0x0F80, which results in 1920 steps for +100 deg and 1920 steps for -100 degs meaning if you take movement a scaled between -1 ... 1 and multiply by 1920 you get the travel from center #define VOLZ_SET_EXTENDED_POSITION_CMD 0xDC #define VOLZ_SET_EXTENDED_POSITION_RSP 0x2C @@ -56,8 +53,7 @@ public: AP_Volz_Protocol(); /* Do not allow copies */ - AP_Volz_Protocol(const AP_Volz_Protocol &other) = delete; - AP_Volz_Protocol &operator=(const AP_Volz_Protocol&) = delete; + CLASS_NO_COPY(AP_Volz_Protocol); static const struct AP_Param::GroupInfo var_info[];