From cdeb1fb8f3cbc990da30b6eb110e5d1edfd445dc Mon Sep 17 00:00:00 2001 From: Matthias Badaire Date: Fri, 16 Jan 2015 08:31:16 +0100 Subject: [PATCH] AP_Mount_Alexmos : changes some define to avoid conflicting change SPEED to AP_MOUNT_ALEXMOS_SPEED and the control mode defines as well --- libraries/AP_Mount/AP_Mount_Alexmos.cpp | 8 ++++---- libraries/AP_Mount/AP_Mount_Alexmos.h | 12 ++++++------ 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp index 39ccd02ce6..8dc659530b 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp +++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp @@ -130,12 +130,12 @@ void AP_Mount_Alexmos::control_axis(const Vector3f& angle, bool target_in_degree target_deg *= RAD_TO_DEG; } - uint8_t mode = MODE_ANGLE; - int16_t speed_roll = DEGREE_PER_SEC_TO_VALUE(SPEED); + uint8_t mode = AP_MOUNT_ALEXMOS_MODE_ANGLE; + int16_t speed_roll = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED); int16_t angle_roll = DEGREE_TO_VALUE(target_deg.x); - int16_t speed_pitch = DEGREE_PER_SEC_TO_VALUE(SPEED); + int16_t speed_pitch = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED); int16_t angle_pitch = DEGREE_TO_VALUE(target_deg.y); - int16_t speed_yaw = DEGREE_PER_SEC_TO_VALUE(SPEED); + int16_t speed_yaw = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED); int16_t angle_yaw = DEGREE_TO_VALUE(target_deg.z); uint8_t data[13] = { (uint8_t)mode, diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index 39ce31b899..e63da5b87f 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -54,13 +54,13 @@ #define CMD_SERVO_OUT 36 #define CMD_ERROR 255 -#define MODE_NO_CONTROL 0 -#define MODE_SPEED 1 -#define MODE_ANGLE 2 -#define MODE_SPEED_ANGLE 3 -#define MODE_RC 4 +#define AP_MOUNT_ALEXMOS_MODE_NO_CONTROL 0 +#define AP_MOUNT_ALEXMOS_MODE_SPEED 1 +#define AP_MOUNT_ALEXMOS_MODE_ANGLE 2 +#define AP_MOUNT_ALEXMOS_MODE_SPEED_ANGLE 3 +#define AP_MOUNT_ALEXMOS_MODE_RC 4 -#define SPEED 30 // degree/s2 +#define AP_MOUNT_ALEXMOS_SPEED 30 // degree/s2 #define VALUE_TO_DEGREE(d) ((float)((d * 720) >> 15)) #define DEGREE_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.02197265625f)))