diff --git a/libraries/AP_Gripper/AP_Gripper_EPM.cpp b/libraries/AP_Gripper/AP_Gripper_EPM.cpp index 7ee41b537c..574d6ff99c 100644 --- a/libraries/AP_Gripper/AP_Gripper_EPM.cpp +++ b/libraries/AP_Gripper/AP_Gripper_EPM.cpp @@ -15,6 +15,8 @@ #include #include #include +#include + #ifdef UAVCAN_NODE_FILE #include #include diff --git a/libraries/AP_Gripper/AP_Gripper_EPM.h b/libraries/AP_Gripper/AP_Gripper_EPM.h index 65ae6a4732..aeb23069a2 100644 --- a/libraries/AP_Gripper/AP_Gripper_EPM.h +++ b/libraries/AP_Gripper/AP_Gripper_EPM.h @@ -19,8 +19,6 @@ #include "AP_Gripper_Backend.h" -#include - #define EPM_RETURN_TO_NEUTRAL_MS 500 // EPM PWM returns to neutral position this many milliseconds after grab or release /// @class AP_Gripper_EPM diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.cpp b/libraries/AP_Gripper/AP_Gripper_Servo.cpp index 45bb387fa3..43f08895a8 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.cpp +++ b/libraries/AP_Gripper/AP_Gripper_Servo.cpp @@ -4,6 +4,7 @@ #include #include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.h b/libraries/AP_Gripper/AP_Gripper_Servo.h index 33042c0e93..3c72effc09 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.h +++ b/libraries/AP_Gripper/AP_Gripper_Servo.h @@ -19,8 +19,6 @@ #if AP_GRIPPER_SERVO_ENABLED -#include - #define SERVO_ACTUATION_TIME 500 // Time for servo to move to target position during grab or release in milliseconds class AP_Gripper_Servo : public AP_Gripper_Backend {