standard.cpp
16 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
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
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file standard.cpp
*
* @author Simon Wilks <simon@uaventure.com>
* @author Roman Bapst <bapstroman@gmail.com>
* @author Andreas Antener <andreas@uaventure.com>
* @author Sander Smeets <sander@droneslab.com>
*
*/
#include "standard.h"
#include "vtol_att_control_main.h"
#include <float.h>
using namespace matrix;
Standard::Standard(VtolAttitudeControl *attc) :
VtolType(attc)
{
_vtol_schedule.flight_mode = vtol_mode::MC_MODE;
_vtol_schedule.transition_start = 0;
_pusher_active = false;
_mc_roll_weight = 1.0f;
_mc_pitch_weight = 1.0f;
_mc_yaw_weight = 1.0f;
_mc_throttle_weight = 1.0f;
_params_handles_standard.pusher_ramp_dt = param_find("VT_PSHER_RMP_DT");
_params_handles_standard.back_trans_ramp = param_find("VT_B_TRANS_RAMP");
_params_handles_standard.pitch_setpoint_offset = param_find("FW_PSP_OFF");
_params_handles_standard.reverse_output = param_find("VT_B_REV_OUT");
_params_handles_standard.reverse_delay = param_find("VT_B_REV_DEL");
}
void
Standard::parameters_update()
{
float v;
/* duration of a forwards transition to fw mode */
param_get(_params_handles_standard.pusher_ramp_dt, &v);
_params_standard.pusher_ramp_dt = math::constrain(v, 0.0f, 20.0f);
/* MC ramp up during back transition to mc mode */
param_get(_params_handles_standard.back_trans_ramp, &v);
_params_standard.back_trans_ramp = math::constrain(v, 0.0f, _params->back_trans_duration);
_airspeed_trans_blend_margin = _params->transition_airspeed - _params->airspeed_blend;
/* pitch setpoint offset */
param_get(_params_handles_standard.pitch_setpoint_offset, &v);
_params_standard.pitch_setpoint_offset = math::radians(v);
/* reverse output */
param_get(_params_handles_standard.reverse_output, &v);
_params_standard.reverse_output = math::constrain(v, 0.0f, 1.0f);
/* reverse output */
param_get(_params_handles_standard.reverse_delay, &v);
_params_standard.reverse_delay = math::constrain(v, 0.0f, 10.0f);
}
void Standard::update_vtol_state()
{
/* After flipping the switch the vehicle will start the pusher (or tractor) motor, picking up
* forward speed. After the vehicle has picked up enough speed the rotors shutdown.
* For the back transition the pusher motor is immediately stopped and rotors reactivated.
*/
float mc_weight = _mc_roll_weight;
float time_since_trans_start = (float)(hrt_absolute_time() - _vtol_schedule.transition_start) * 1e-6f;
if (_vtol_vehicle_status->vtol_transition_failsafe) {
// Failsafe event, engage mc motors immediately
_vtol_schedule.flight_mode = vtol_mode::MC_MODE;
_pusher_throttle = 0.0f;
_reverse_output = 0.0f;
//reset failsafe when FW is no longer requested
if (!_attc->is_fixed_wing_requested()) {
_vtol_vehicle_status->vtol_transition_failsafe = false;
}
} else if (!_attc->is_fixed_wing_requested()) {
// the transition to fw mode switch is off
if (_vtol_schedule.flight_mode == vtol_mode::MC_MODE) {
// in mc mode
_vtol_schedule.flight_mode = vtol_mode::MC_MODE;
mc_weight = 1.0f;
_pusher_throttle = 0.0f;
_reverse_output = 0.0f;
} else if (_vtol_schedule.flight_mode == vtol_mode::FW_MODE) {
// Regular backtransition
_vtol_schedule.flight_mode = vtol_mode::TRANSITION_TO_MC;
_vtol_schedule.transition_start = hrt_absolute_time();
_reverse_output = _params_standard.reverse_output;
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_FW) {
// failsafe back to mc mode
_vtol_schedule.flight_mode = vtol_mode::MC_MODE;
mc_weight = 1.0f;
_pusher_throttle = 0.0f;
_reverse_output = 0.0f;
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_MC) {
// transition to MC mode if transition time has passed or forward velocity drops below MPC cruise speed
const Dcmf R_to_body(Quatf(_v_att->q).inversed());
const Vector3f vel = R_to_body * Vector3f(_local_pos->vx, _local_pos->vy, _local_pos->vz);
float x_vel = vel(0);
if (time_since_trans_start > _params->back_trans_duration ||
(_local_pos->v_xy_valid && x_vel <= _params->mpc_xy_cruise) ||
can_transition_on_ground()) {
_vtol_schedule.flight_mode = vtol_mode::MC_MODE;
}
}
} else {
// the transition to fw mode switch is on
if (_vtol_schedule.flight_mode == vtol_mode::MC_MODE || _vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_MC) {
// start transition to fw mode
/* NOTE: The failsafe transition to fixed-wing was removed because it can result in an
* unsafe flying state. */
_vtol_schedule.flight_mode = vtol_mode::TRANSITION_TO_FW;
_vtol_schedule.transition_start = hrt_absolute_time();
} else if (_vtol_schedule.flight_mode == vtol_mode::FW_MODE) {
// in fw mode
_vtol_schedule.flight_mode = vtol_mode::FW_MODE;
mc_weight = 0.0f;
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_FW) {
// continue the transition to fw mode while monitoring airspeed for a final switch to fw mode
const bool airspeed_triggers_transition = PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)
&& !_params->airspeed_disabled;
const bool minimum_trans_time_elapsed = time_since_trans_start > _params->front_trans_time_min;
bool transition_to_fw = false;
if (minimum_trans_time_elapsed) {
if (airspeed_triggers_transition) {
transition_to_fw = _airspeed_validated->calibrated_airspeed_m_s >= _params->transition_airspeed;
} else {
transition_to_fw = true;
}
}
transition_to_fw |= can_transition_on_ground();
if (transition_to_fw) {
_vtol_schedule.flight_mode = vtol_mode::FW_MODE;
// don't set pusher throttle here as it's being ramped up elsewhere
_trans_finished_ts = hrt_absolute_time();
}
}
}
_mc_roll_weight = mc_weight;
_mc_pitch_weight = mc_weight;
_mc_yaw_weight = mc_weight;
_mc_throttle_weight = mc_weight;
// map specific control phases to simple control modes
switch (_vtol_schedule.flight_mode) {
case vtol_mode::MC_MODE:
_vtol_mode = mode::ROTARY_WING;
break;
case vtol_mode::FW_MODE:
_vtol_mode = mode::FIXED_WING;
break;
case vtol_mode::TRANSITION_TO_FW:
_vtol_mode = mode::TRANSITION_TO_FW;
break;
case vtol_mode::TRANSITION_TO_MC:
_vtol_mode = mode::TRANSITION_TO_MC;
break;
}
}
void Standard::update_transition_state()
{
float mc_weight = 1.0f;
float time_since_trans_start = (float)(hrt_absolute_time() - _vtol_schedule.transition_start) * 1e-6f;
VtolType::update_transition_state();
// copy virtual attitude setpoint to real attitude setpoint
memcpy(_v_att_sp, _mc_virtual_att_sp, sizeof(vehicle_attitude_setpoint_s));
if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_FW) {
if (_params_standard.pusher_ramp_dt <= 0.0f) {
// just set the final target throttle value
_pusher_throttle = _params->front_trans_throttle;
} else if (_pusher_throttle <= _params->front_trans_throttle) {
// ramp up throttle to the target throttle value
_pusher_throttle = _params->front_trans_throttle * time_since_trans_start / _params_standard.pusher_ramp_dt;
}
// do blending of mc and fw controls if a blending airspeed has been provided and the minimum transition time has passed
if (_airspeed_trans_blend_margin > 0.0f &&
PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s) &&
_airspeed_validated->calibrated_airspeed_m_s > 0.0f &&
_airspeed_validated->calibrated_airspeed_m_s >= _params->airspeed_blend &&
time_since_trans_start > _params->front_trans_time_min) {
mc_weight = 1.0f - fabsf(_airspeed_validated->calibrated_airspeed_m_s - _params->airspeed_blend) /
_airspeed_trans_blend_margin;
// time based blending when no airspeed sensor is set
} else if (_params->airspeed_disabled || !PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)) {
mc_weight = 1.0f - time_since_trans_start / _params->front_trans_time_min;
mc_weight = math::constrain(2.0f * mc_weight, 0.0f, 1.0f);
}
// ramp up FW_PSP_OFF
_v_att_sp->pitch_body = _params_standard.pitch_setpoint_offset * (1.0f - mc_weight);
_v_att_sp->roll_body = _fw_virtual_att_sp->roll_body;
// in stabilized, acro or manual mode, set the MC thrust to the throttle stick position (coming from the FW attitude setpoint)
if (!_v_control_mode->flag_control_climb_rate_enabled) {
_v_att_sp->thrust_body[2] = -_fw_virtual_att_sp->thrust_body[0];
}
const Quatf q_sp(Eulerf(_v_att_sp->roll_body, _v_att_sp->pitch_body, _v_att_sp->yaw_body));
q_sp.copyTo(_v_att_sp->q_d);
// check front transition timeout
if (_params->front_trans_timeout > FLT_EPSILON) {
if (time_since_trans_start > _params->front_trans_timeout) {
// transition timeout occured, abort transition
_attc->quadchute("Transition timeout");
}
}
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_MC) {
_v_att_sp->roll_body = _fw_virtual_att_sp->roll_body;
if (_v_control_mode->flag_control_climb_rate_enabled) {
// control backtransition deceleration using pitch.
_v_att_sp->pitch_body = update_and_get_backtransition_pitch_sp();
}
// in stabilized, acro or manual mode, set the MC thrust to the throttle stick position (coming from the FW attitude setpoint)
if (!_v_control_mode->flag_control_climb_rate_enabled) {
_v_att_sp->thrust_body[2] = -_fw_virtual_att_sp->thrust_body[0];
}
const Quatf q_sp(Eulerf(_v_att_sp->roll_body, _v_att_sp->pitch_body, _v_att_sp->yaw_body));
q_sp.copyTo(_v_att_sp->q_d);
_pusher_throttle = 0.0f;
if (time_since_trans_start >= _params_standard.reverse_delay) {
// Handle throttle reversal for active breaking
float thrscale = (time_since_trans_start - _params_standard.reverse_delay) / (_params_standard.pusher_ramp_dt);
thrscale = math::constrain(thrscale, 0.0f, 1.0f);
_pusher_throttle = thrscale * _params->back_trans_throttle;
}
// continually increase mc attitude control as we transition back to mc mode
if (_params_standard.back_trans_ramp > FLT_EPSILON) {
mc_weight = time_since_trans_start / _params_standard.back_trans_ramp;
}
set_all_motor_state(motor_state::ENABLED);
// set idle speed for MC actuators
if (!_flag_idle_mc) {
_flag_idle_mc = set_idle_mc();
}
}
mc_weight = math::constrain(mc_weight, 0.0f, 1.0f);
_mc_roll_weight = mc_weight;
_mc_pitch_weight = mc_weight;
_mc_yaw_weight = mc_weight;
_mc_throttle_weight = mc_weight;
}
void Standard::update_mc_state()
{
VtolType::update_mc_state();
_pusher_throttle = VtolType::pusher_assist();
}
void Standard::update_fw_state()
{
VtolType::update_fw_state();
}
/**
* Prepare message to acutators with data from mc and fw attitude controllers. An mc attitude weighting will determine
* what proportion of control should be applied to each of the control groups (mc and fw).
*/
void Standard::fill_actuator_outputs()
{
auto &mc_in = _actuators_mc_in->control;
auto &fw_in = _actuators_fw_in->control;
auto &mc_out = _actuators_out_0->control;
auto &fw_out = _actuators_out_1->control;
const bool elevon_lock = (_params->elevons_mc_lock == 1);
switch (_vtol_schedule.flight_mode) {
case vtol_mode::MC_MODE:
// MC out = MC in
mc_out[actuator_controls_s::INDEX_ROLL] = mc_in[actuator_controls_s::INDEX_ROLL];
mc_out[actuator_controls_s::INDEX_PITCH] = mc_in[actuator_controls_s::INDEX_PITCH];
mc_out[actuator_controls_s::INDEX_YAW] = mc_in[actuator_controls_s::INDEX_YAW];
mc_out[actuator_controls_s::INDEX_THROTTLE] = mc_in[actuator_controls_s::INDEX_THROTTLE];
mc_out[actuator_controls_s::INDEX_LANDING_GEAR] = mc_in[actuator_controls_s::INDEX_LANDING_GEAR];
// FW out = 0, other than roll and pitch depending on elevon lock
fw_out[actuator_controls_s::INDEX_ROLL] = elevon_lock ? 0 : fw_in[actuator_controls_s::INDEX_ROLL];
fw_out[actuator_controls_s::INDEX_PITCH] = elevon_lock ? 0 : fw_in[actuator_controls_s::INDEX_PITCH];
fw_out[actuator_controls_s::INDEX_YAW] = 0;
fw_out[actuator_controls_s::INDEX_THROTTLE] = _pusher_throttle;
fw_out[actuator_controls_s::INDEX_FLAPS] = 0;
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = 0;
break;
case vtol_mode::TRANSITION_TO_FW:
// FALLTHROUGH
case vtol_mode::TRANSITION_TO_MC:
// MC out = MC in (weighted)
mc_out[actuator_controls_s::INDEX_ROLL] = mc_in[actuator_controls_s::INDEX_ROLL] * _mc_roll_weight;
mc_out[actuator_controls_s::INDEX_PITCH] = mc_in[actuator_controls_s::INDEX_PITCH] * _mc_pitch_weight;
mc_out[actuator_controls_s::INDEX_YAW] = mc_in[actuator_controls_s::INDEX_YAW] * _mc_yaw_weight;
mc_out[actuator_controls_s::INDEX_THROTTLE] = mc_in[actuator_controls_s::INDEX_THROTTLE] * _mc_throttle_weight;
mc_out[actuator_controls_s::INDEX_LANDING_GEAR] = 0;
// FW out = FW in, with VTOL transition controlling throttle and airbrakes
fw_out[actuator_controls_s::INDEX_ROLL] = fw_in[actuator_controls_s::INDEX_ROLL];
fw_out[actuator_controls_s::INDEX_PITCH] = fw_in[actuator_controls_s::INDEX_PITCH];
fw_out[actuator_controls_s::INDEX_YAW] = fw_in[actuator_controls_s::INDEX_YAW];
fw_out[actuator_controls_s::INDEX_THROTTLE] = _pusher_throttle;
fw_out[actuator_controls_s::INDEX_FLAPS] = fw_in[actuator_controls_s::INDEX_FLAPS];
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = _reverse_output;
break;
case vtol_mode::FW_MODE:
// MC out = 0
mc_out[actuator_controls_s::INDEX_ROLL] = 0;
mc_out[actuator_controls_s::INDEX_PITCH] = 0;
mc_out[actuator_controls_s::INDEX_YAW] = 0;
mc_out[actuator_controls_s::INDEX_THROTTLE] = 0;
mc_out[actuator_controls_s::INDEX_LANDING_GEAR] = 0;
// FW out = FW in
fw_out[actuator_controls_s::INDEX_ROLL] = fw_in[actuator_controls_s::INDEX_ROLL];
fw_out[actuator_controls_s::INDEX_PITCH] = fw_in[actuator_controls_s::INDEX_PITCH];
fw_out[actuator_controls_s::INDEX_YAW] = fw_in[actuator_controls_s::INDEX_YAW];
fw_out[actuator_controls_s::INDEX_THROTTLE] = fw_in[actuator_controls_s::INDEX_THROTTLE];
fw_out[actuator_controls_s::INDEX_FLAPS] = fw_in[actuator_controls_s::INDEX_FLAPS];
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = 0;
break;
}
_actuators_out_0->timestamp_sample = _actuators_mc_in->timestamp_sample;
_actuators_out_1->timestamp_sample = _actuators_fw_in->timestamp_sample;
_actuators_out_0->timestamp = _actuators_out_1->timestamp = hrt_absolute_time();
}
void
Standard::waiting_on_tecs()
{
// keep thrust from transition
_v_att_sp->thrust_body[0] = _pusher_throttle;
};