Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/AntennaTracker/mode.cpp
9354 views
1
#include "mode.h"
2
3
#include "Tracker.h"
4
5
void Mode::update_auto(void)
6
{
7
struct Tracker::NavStatus &nav_status = tracker.nav_status;
8
9
Parameters &g = tracker.g;
10
11
float yaw_deg = wrap_180(nav_status.bearing + g.yaw_trim); // target yaw in degrees
12
float pitch_deg = constrain_float(nav_status.pitch + g.pitch_trim, g.pitch_min, g.pitch_max); // target pitch in degrees
13
tracker.mode_auto.set_target(yaw_deg, pitch_deg);
14
15
float yaw = yaw_deg * 100; // target yaw in centidegrees
16
float pitch = pitch_deg * 100; // target pitch in centidegrees
17
18
bool direction_reversed = get_ef_yaw_direction();
19
20
calc_angle_error(pitch, yaw, direction_reversed);
21
22
float bf_pitch;
23
float bf_yaw;
24
convert_ef_to_bf(pitch, yaw, bf_pitch, bf_yaw);
25
26
// only move servos if target is at least distance_min away if we have a target
27
if ((g.distance_min <= 0) || (nav_status.distance >= g.distance_min) || !tracker.vehicle.location_valid) {
28
tracker.update_pitch_servo(bf_pitch);
29
tracker.update_yaw_servo(bf_yaw);
30
}
31
}
32
33
void Mode::update_scan(void)
34
{
35
struct Tracker::NavStatus &nav_status = tracker.nav_status;
36
37
Parameters &g = tracker.g;
38
39
if (!nav_status.manual_control_yaw) {
40
float yaw_delta = g.scan_speed_yaw * 0.02f;
41
nav_status.bearing += yaw_delta * (nav_status.scan_reverse_yaw?-1:1);
42
if (nav_status.bearing < 0 && nav_status.scan_reverse_yaw) {
43
nav_status.scan_reverse_yaw = false;
44
}
45
if (nav_status.bearing > 360 && !nav_status.scan_reverse_yaw) {
46
nav_status.scan_reverse_yaw = true;
47
}
48
nav_status.bearing = constrain_float(nav_status.bearing, 0, 360);
49
}
50
51
if (!nav_status.manual_control_pitch) {
52
const float pitch_delta = g.scan_speed_pitch * 0.02f;
53
if (nav_status.scan_reverse_pitch) {
54
nav_status.pitch -= pitch_delta;
55
if (nav_status.pitch < g.pitch_min) {
56
nav_status.scan_reverse_pitch = false;
57
}
58
} else {
59
nav_status.pitch += pitch_delta;
60
if (nav_status.pitch > g.pitch_max) {
61
nav_status.scan_reverse_pitch = true;
62
}
63
}
64
nav_status.pitch = constrain_float(nav_status.pitch, g.pitch_min, g.pitch_max);
65
}
66
67
update_auto();
68
}
69
70
void Mode::calc_angle_error(float pitch, float yaw, bool direction_reversed)
71
{
72
// Pitch angle error in centidegrees
73
// Positive error means the target is above current pitch
74
// Negative error means the target is below current pitch
75
const AP_AHRS &ahrs = AP::ahrs();
76
float ahrs_pitch = ahrs.pitch_sensor;
77
int32_t ef_pitch_angle_error = pitch - ahrs_pitch;
78
79
// Yaw angle error in centidegrees
80
// Positive error means the target is right of current yaw
81
// Negative error means the target is left of current yaw
82
int32_t ahrs_yaw_cd = wrap_180_cd(ahrs.yaw_sensor);
83
int32_t ef_yaw_angle_error = wrap_180_cd(yaw - ahrs_yaw_cd);
84
if (direction_reversed) {
85
if (ef_yaw_angle_error > 0) {
86
ef_yaw_angle_error = (yaw - ahrs_yaw_cd) - 36000;
87
} else {
88
ef_yaw_angle_error = 36000 + (yaw - ahrs_yaw_cd);
89
}
90
}
91
92
// earth frame to body frame angle error conversion
93
float bf_pitch_err;
94
float bf_yaw_err;
95
convert_ef_to_bf(ef_pitch_angle_error, ef_yaw_angle_error, bf_pitch_err, bf_yaw_err);
96
struct Tracker::NavStatus &nav_status = tracker.nav_status;
97
nav_status.angle_error_pitch = bf_pitch_err;
98
nav_status.angle_error_yaw = bf_yaw_err;
99
100
// set actual and desired for logging, note we are using angles not rates
101
Parameters &g = tracker.g;
102
g.pidPitch2Srv.set_target_rate(pitch * 0.01);
103
g.pidPitch2Srv.set_actual_rate(ahrs_pitch * 0.01);
104
g.pidYaw2Srv.set_target_rate(yaw * 0.01);
105
g.pidYaw2Srv.set_actual_rate(ahrs_yaw_cd * 0.01);
106
}
107
108
void Mode::convert_ef_to_bf(float pitch, float yaw, float& bf_pitch, float& bf_yaw)
109
{
110
// earth frame to body frame pitch and yaw conversion
111
const AP_AHRS &ahrs = AP::ahrs();
112
bf_pitch = ahrs.cos_roll() * pitch + ahrs.sin_roll() * ahrs.cos_pitch() * yaw;
113
bf_yaw = -ahrs.sin_roll() * pitch + ahrs.cos_pitch() * ahrs.cos_roll() * yaw;
114
}
115
116
bool Mode::convert_bf_to_ef(float pitch, float yaw, float& ef_pitch, float& ef_yaw)
117
{
118
const AP_AHRS &ahrs = AP::ahrs();
119
// avoid divide by zero
120
if (is_zero(ahrs.cos_pitch())) {
121
return false;
122
}
123
// convert earth frame angle or rates to body frame
124
ef_pitch = ahrs.cos_roll() * pitch - ahrs.sin_roll() * yaw;
125
ef_yaw = (ahrs.sin_roll() / ahrs.cos_pitch()) * pitch + (ahrs.cos_roll() / ahrs.cos_pitch()) * yaw;
126
return true;
127
}
128
129
// return value is true if taking the long road to the target, false if normal, shortest direction should be used
130
bool Mode::get_ef_yaw_direction()
131
{
132
// calculating distances from current pitch/yaw to lower and upper limits in centi-degrees
133
Parameters &g = tracker.g;
134
float yaw_angle_limit_lower = (-g.yaw_range * 100.0f / 2.0f) - tracker.yaw_servo_out_filt.get();
135
float yaw_angle_limit_upper = (g.yaw_range * 100.0f / 2.0f) - tracker.yaw_servo_out_filt.get();
136
float pitch_angle_limit_lower = (g.pitch_min * 100.0f) - tracker.pitch_servo_out_filt.get();
137
float pitch_angle_limit_upper = (g.pitch_max * 100.0f) - tracker.pitch_servo_out_filt.get();
138
139
// distances to earthframe angle limits in centi-degrees
140
float ef_yaw_limit_lower = yaw_angle_limit_lower;
141
float ef_yaw_limit_upper = yaw_angle_limit_upper;
142
float ef_pitch_limit_lower = pitch_angle_limit_lower;
143
float ef_pitch_limit_upper = pitch_angle_limit_upper;
144
convert_bf_to_ef(pitch_angle_limit_lower, yaw_angle_limit_lower, ef_pitch_limit_lower, ef_yaw_limit_lower);
145
convert_bf_to_ef(pitch_angle_limit_upper, yaw_angle_limit_upper, ef_pitch_limit_upper, ef_yaw_limit_upper);
146
147
const AP_AHRS &ahrs = AP::ahrs();
148
float ef_yaw_current = wrap_180_cd(ahrs.yaw_sensor);
149
struct Tracker::NavStatus &nav_status = tracker.nav_status;
150
float ef_yaw_target = wrap_180_cd((nav_status.bearing+g.yaw_trim)*100);
151
float ef_yaw_angle_error = wrap_180_cd(ef_yaw_target - ef_yaw_current);
152
153
// calculate angle error to target in both directions (i.e. moving up/right or lower/left)
154
float yaw_angle_error_upper;
155
float yaw_angle_error_lower;
156
if (ef_yaw_angle_error >= 0) {
157
yaw_angle_error_upper = ef_yaw_angle_error;
158
yaw_angle_error_lower = ef_yaw_angle_error - 36000;
159
} else {
160
yaw_angle_error_upper = 36000 + ef_yaw_angle_error;
161
yaw_angle_error_lower = ef_yaw_angle_error;
162
}
163
164
// checks that the vehicle is outside the tracker's range
165
if ((yaw_angle_error_lower < ef_yaw_limit_lower) && (yaw_angle_error_upper > ef_yaw_limit_upper)) {
166
// if the tracker is trying to move clockwise to reach the vehicle,
167
// but the tracker could get closer to the vehicle by moving counter-clockwise then set direction_reversed to true
168
if (ef_yaw_angle_error>0 && ((ef_yaw_limit_lower - yaw_angle_error_lower) < (yaw_angle_error_upper - ef_yaw_limit_upper))) {
169
return true;
170
}
171
// if the tracker is trying to move counter-clockwise to reach the vehicle,
172
// but the tracker could get closer to the vehicle by moving then set direction_reversed to true
173
if (ef_yaw_angle_error<0 && ((ef_yaw_limit_lower - yaw_angle_error_lower) > (yaw_angle_error_upper - ef_yaw_limit_upper))) {
174
return true;
175
}
176
}
177
178
// if we get this far we can use the regular, shortest path to the target
179
return false;
180
}
181
182