-
Notifications
You must be signed in to change notification settings - Fork 18.5k
/
Copy pathmode_loiter.cpp
218 lines (178 loc) · 7.49 KB
/
mode_loiter.cpp
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
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
#include "Copter.h"
#if MODE_LOITER_ENABLED
/*
* Init and run calls for loiter flight mode
*/
// loiter_init - initialise loiter controller
bool ModeLoiter::init(bool ignore_checks)
{
if (!copter.failsafe.radio) {
float target_roll, target_pitch;
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// convert pilot input to lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max_cd());
// process pilot's roll and pitch input
loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch);
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
loiter_nav->clear_pilot_desired_acceleration();
}
loiter_nav->init_target();
// initialise the vertical position controller
if (!pos_control->is_active_z()) {
pos_control->init_z_controller();
}
// set vertical speed and acceleration limits
pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
pos_control->set_correction_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
#if AC_PRECLAND_ENABLED
_precision_loiter_active = false;
#endif
return true;
}
#if AC_PRECLAND_ENABLED
bool ModeLoiter::do_precision_loiter()
{
if (!_precision_loiter_enabled) {
return false;
}
if (copter.ap.land_complete_maybe) {
return false; // don't move on the ground
}
// if the pilot *really* wants to move the vehicle, let them....
if (loiter_nav->get_pilot_desired_acceleration().length() > 50.0f) {
return false;
}
if (!copter.precland.target_acquired()) {
return false; // we don't have a good vector
}
return true;
}
void ModeLoiter::precision_loiter_xy()
{
loiter_nav->clear_pilot_desired_acceleration();
Vector2f target_pos, target_vel;
if (!copter.precland.get_target_position_cm(target_pos)) {
target_pos = inertial_nav.get_position_xy_cm();
}
// get the velocity of the target
copter.precland.get_target_velocity_cms(inertial_nav.get_velocity_xy_cms(), target_vel);
Vector2f zero;
Vector2p landing_pos = target_pos.topostype();
// target vel will remain zero if landing target is stationary
pos_control->input_pos_vel_accel_xy(landing_pos, target_vel, zero);
// run pos controller
pos_control->update_xy_controller();
}
#endif
// loiter_run - runs the loiter controller
// should be called at 100hz or more
void ModeLoiter::run()
{
float target_roll, target_pitch;
float target_yaw_rate = 0.0f;
float target_climb_rate = 0.0f;
// set vertical speed and acceleration limits
pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
// process pilot inputs unless we are in radio failsafe
if (!copter.failsafe.radio) {
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// convert pilot input to lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max_cd());
// process pilot's roll and pitch input
loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate();
// get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up);
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
loiter_nav->clear_pilot_desired_acceleration();
}
// relax loiter target if we might be landed
if (copter.ap.land_complete_maybe) {
loiter_nav->soften_for_landing();
}
// Loiter State Machine Determination
AltHoldModeState loiter_state = get_alt_hold_state(target_climb_rate);
// Loiter State Machine
switch (loiter_state) {
case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->init_target();
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);
break;
case AltHoldModeState::Landed_Ground_Idle:
attitude_control->reset_yaw_target_and_rate();
FALLTHROUGH;
case AltHoldModeState::Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms_smoothly();
loiter_nav->init_target();
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
break;
case AltHoldModeState::Takeoff:
// initiate take-off
if (!takeoff.running()) {
takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
}
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
// set position controller targets adjusted for pilot input
takeoff.do_pilot_takeoff(target_climb_rate);
// run loiter controller
loiter_nav->update();
// call attitude controller
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);
break;
case AltHoldModeState::Flying:
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
#if AC_PRECLAND_ENABLED
bool precision_loiter_old_state = _precision_loiter_active;
if (do_precision_loiter()) {
precision_loiter_xy();
_precision_loiter_active = true;
} else {
_precision_loiter_active = false;
}
if (precision_loiter_old_state && !_precision_loiter_active) {
// prec loiter was active, not any more, let's init again as user takes control
loiter_nav->init_target();
}
// run loiter controller if we are not doing prec loiter
if (!_precision_loiter_active) {
loiter_nav->update();
}
#else
loiter_nav->update();
#endif
// call attitude controller
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
#if AP_RANGEFINDER_ENABLED
// update the vertical offset based on the surface measurement
copter.surface_tracking.update_surface_offset();
#endif
// Send the commanded climb rate to the position controller
pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate);
break;
}
// run the vertical position controller and set output throttle
pos_control->update_z_controller();
}
uint32_t ModeLoiter::wp_distance() const
{
return loiter_nav->get_distance_to_target();
}
int32_t ModeLoiter::wp_bearing() const
{
return loiter_nav->get_bearing_to_target();
}
#endif