forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathAP_Mount_Servo.cpp
More file actions
162 lines (133 loc) · 5.54 KB
/
AP_Mount_Servo.cpp
File metadata and controls
162 lines (133 loc) · 5.54 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
#include "AP_Mount_config.h"
#if HAL_MOUNT_SERVO_ENABLED
#include "AP_Mount_Servo.h"
#include <AP_AHRS/AP_AHRS.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
extern const AP_HAL::HAL& hal;
// init - performs any required initialisation for this instance
void AP_Mount_Servo::init()
{
if (_instance == 0) {
_roll_idx = SRV_Channel::k_mount_roll;
_tilt_idx = SRV_Channel::k_mount_tilt;
_pan_idx = SRV_Channel::k_mount_pan;
} else {
// this must be the 2nd mount
_roll_idx = SRV_Channel::k_mount2_roll;
_tilt_idx = SRV_Channel::k_mount2_tilt;
_pan_idx = SRV_Channel::k_mount2_pan;
}
AP_Mount_Backend::init();
}
// update mount position - should be called periodically
void AP_Mount_Servo::update()
{
AP_Mount_Backend::update();
update_mnt_target();
// have our base class call send_target_angles to command the gimbal:
send_target_to_gimbal();
}
// called by the backend to set the servo angles:
void AP_Mount_Servo::send_target_angles(const MountAngleTarget& angle_rad)
{
update_angle_outputs(mnt_target.angle_rad);
// write the results to the servos
move_servo(_roll_idx, degrees(_angle_bf_output_rad.x)*10, _params.roll_angle_min*10, _params.roll_angle_max*10);
move_servo(_tilt_idx, degrees(_angle_bf_output_rad.y)*10, _params.pitch_angle_min*10, _params.pitch_angle_max*10);
move_servo(_pan_idx, degrees(_angle_bf_output_rad.z)*10, _params.yaw_angle_min*10, _params.yaw_angle_max*10);
}
// returns true if this mount can control its roll
bool AP_Mount_Servo::has_roll_control() const
{
return SRV_Channels::function_assigned(_roll_idx) && roll_range_valid();
}
// returns true if this mount can control its tilt
bool AP_Mount_Servo::has_pitch_control() const
{
return SRV_Channels::function_assigned(_tilt_idx) && pitch_range_valid();
}
// returns true if this mount can control its pan (required for multicopters)
bool AP_Mount_Servo::has_pan_control() const
{
return SRV_Channels::function_assigned(_pan_idx) && yaw_range_valid();
}
// get attitude as a quaternion. returns true on success
bool AP_Mount_Servo::get_attitude_quaternion(Quaternion& att_quat)
{
// No feedback from gimbal so simply report demanded servo angles (which is
// not the same as target angles).
float roll_rad = 0.0f;
float pitch_rad = 0.0f;
float yaw_rad = 0.0f;
if (has_roll_control()) {
roll_rad = constrain_float(_angle_bf_output_rad.x, radians(_params.roll_angle_min), radians(_params.roll_angle_max));
}
if (has_pitch_control()) {
pitch_rad = constrain_float(_angle_bf_output_rad.y, radians(_params.pitch_angle_min), radians(_params.pitch_angle_max));
}
if (has_pan_control()) {
yaw_rad = constrain_float(_angle_bf_output_rad.z, radians(_params.yaw_angle_min), radians(_params.yaw_angle_max));
}
// convert to quaternion
att_quat.from_euler(roll_rad, pitch_rad, yaw_rad);
return true;
}
// private methods
// update body-frame angle outputs from earth-frame angle targets
void AP_Mount_Servo::update_angle_outputs(const MountAngleTarget& angle_rad)
{
const AP_AHRS &ahrs = AP::ahrs();
// get target yaw in body-frame with limits applied
const float yaw_bf_rad = constrain_float(angle_rad.get_bf_yaw(), radians(_params.yaw_angle_min), radians(_params.yaw_angle_max));
// default output to target earth-frame roll and pitch angles, body-frame yaw
_angle_bf_output_rad.x = angle_rad.roll;
_angle_bf_output_rad.y = angle_rad.pitch;
_angle_bf_output_rad.z = yaw_bf_rad;
// do no stabilization in retract or neutral:
switch (mnt_target.target_type) {
case MountTargetType::NEUTRAL:
case MountTargetType::RETRACTED:
return;
case MountTargetType::ANGLE:
case MountTargetType::RATE:
case MountTargetType::LOCATION:
break;
}
// only have to adjust roll/pitch for body frame in self-stabilising brushless gimbals
if (!requires_stabilization) {
//since this is a shared backend, must call this directly
AP_Mount_Backend::adjust_mnt_target_if_RP_locked();
return;
}
// retrieve lean angles from ahrs
Vector2f ahrs_angle_rad = {ahrs.get_roll_rad(), ahrs.get_pitch_rad()};
// rotate ahrs roll and pitch angles to gimbal yaw
if (has_pan_control()) {
ahrs_angle_rad.rotate(-yaw_bf_rad);
}
// add roll and pitch lean angle correction for earth frame
if (angle_rad.roll_is_ef){
_angle_bf_output_rad.x -= ahrs_angle_rad.x;
}
if (angle_rad.pitch_is_ef){
_angle_bf_output_rad.y -= ahrs_angle_rad.y;
}
// lead filter
const Vector3f &gyro = ahrs.get_gyro();
if (!is_zero(_params.roll_stb_lead) && fabsf(ahrs.get_pitch_rad()) < M_PI/3.0f) {
// Compute rate of change of euler roll angle
float roll_rate = gyro.x + (ahrs.sin_pitch() / ahrs.cos_pitch()) * (gyro.y * ahrs.sin_roll() + gyro.z * ahrs.cos_roll());
_angle_bf_output_rad.x -= roll_rate * _params.roll_stb_lead;
}
if (!is_zero(_params.pitch_stb_lead)) {
// Compute rate of change of euler pitch angle
float pitch_rate = ahrs.cos_pitch() * gyro.y - ahrs.sin_roll() * gyro.z;
_angle_bf_output_rad.y -= pitch_rate * _params.pitch_stb_lead;
}
}
// move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10
void AP_Mount_Servo::move_servo(uint8_t function_idx, int16_t angle, int16_t angle_min, int16_t angle_max)
{
SRV_Channels::move_servo((SRV_Channel::Function)function_idx, angle, angle_min, angle_max);
}
#endif // HAL_MOUNT_SERVO_ENABLED