mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Mount: viewpro formatting fix
This commit is contained in:
parent
70cf9de970
commit
0ccf41b525
@ -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)
|
||||
}
|
||||
|
@ -117,10 +117,10 @@ private:
|
||||
|
||||
// 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
|
||||
|
Loading…
Reference in New Issue
Block a user