AP_RobotisServo: allow RobotisServo protocol to be compiled out

This commit is contained in:
Peter Barker 2022-04-08 17:20:57 +10:00 committed by Andrew Tridgell
parent 73b86ccc04
commit 9001058d12
2 changed files with 16 additions and 5 deletions

View File

@ -34,15 +34,15 @@
* limitations under the License. * limitations under the License.
*/ */
#include "AP_RobotisServo.h"
#if AP_ROBOTISSERVO_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_SerialManager/AP_SerialManager.h> #include <AP_SerialManager/AP_SerialManager.h>
#include <SRV_Channel/SRV_Channel.h> #include <SRV_Channel/SRV_Channel.h>
#include "AP_RobotisServo.h"
#if NUM_SERVO_CHANNELS
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#define BROADCAST_ID 0xFE #define BROADCAST_ID 0xFE
@ -406,4 +406,5 @@ void AP_RobotisServo::update()
send_command(i+1, REG_GOAL_POSITION, value, 4); send_command(i+1, REG_GOAL_POSITION, value, 4);
} }
} }
#endif //NUM_SERVO_CHANNELS
#endif // AP_ROBOTISSERVO_ENABLED

View File

@ -18,6 +18,14 @@
#pragma once #pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef AP_ROBOTISSERVO_ENABLED
#define AP_ROBOTISSERVO_ENABLED 1
#endif
#if AP_ROBOTISSERVO_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h> #include <AP_Param/AP_Param.h>
@ -65,3 +73,5 @@ private:
uint32_t last_send_us; uint32_t last_send_us;
uint32_t delay_time_us; uint32_t delay_time_us;
}; };
#endif // AP_ROBOTISSERVO_ENABLED