From b6c67edd8272bdf12ecb96fdbef262d0fd6acf1a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 19 Jul 2023 09:47:58 +0900 Subject: [PATCH] AP_Mount: viewpro formatting fix --- libraries/AP_Mount/AP_Mount_Viewpro.cpp | 6 +++--- libraries/AP_Mount/AP_Mount_Viewpro.h | 8 ++++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index db6ea1ff421c5f..df67923f0e61f9 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -474,7 +474,7 @@ bool AP_Mount_Viewpro::set_lock(bool lock) const A1Packet a1_packet { .content = { frame_id: FrameId::A1, - servo_status: lock ? ServoStatus::follow_yaw_disable : ServoStatus::follow_yaw + servo_status: lock ? ServoStatus::FOLLOW_YAW_DISABLE : ServoStatus::FOLLOW_YAW } }; @@ -518,7 +518,7 @@ bool AP_Mount_Viewpro::send_target_rates(float pitch_rads, float yaw_rads, bool const A1Packet a1_packet { .content = { frame_id: FrameId::A1, - servo_status: ServoStatus::manual_speed_mode, + servo_status: ServoStatus::MANUAL_SPEED_MODE, yaw_be: htobe16(yaw_rate_output), pitch_be: htobe16(pitch_rate_output) } @@ -556,7 +556,7 @@ bool AP_Mount_Viewpro::send_target_angles(float pitch_rad, float yaw_rad, bool y const A1Packet a1_packet { .content = { frame_id: FrameId::A1, - servo_status: ServoStatus::manual_absolute_angle_mode, + servo_status: ServoStatus::MANUAL_ABSOLUTE_ANGLE_MODE, yaw_be: htobe16(yaw_angle_output), pitch_be: htobe16(pitch_angle_output) } diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.h b/libraries/AP_Mount/AP_Mount_Viewpro.h index c22fbad079157e..ab9c89b7def415 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.h +++ b/libraries/AP_Mount/AP_Mount_Viewpro.h @@ -117,10 +117,10 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // A1 servo status enum (used in A1, B1 packets) enum class ServoStatus : uint8_t { - manual_speed_mode = 0x01, - follow_yaw = 0x03, - manual_absolute_angle_mode = 0x0B, - follow_yaw_disable = 0x0A, + MANUAL_SPEED_MODE = 0x01, + FOLLOW_YAW = 0x03, + MANUAL_ABSOLUTE_ANGLE_MODE = 0x0B, + FOLLOW_YAW_DISABLE = 0x0A, }; // C1 image sensor choice