MulticopterPositionControl.cpp
21.1 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
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
/****************************************************************************
*
* Copyright (c) 2013-2020 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.
*
****************************************************************************/
#include "MulticopterPositionControl.hpp"
#include <float.h>
#include <lib/mathlib/mathlib.h>
#include <lib/matrix/matrix/math.hpp>
#include "PositionControl/ControlMath.hpp"
using namespace matrix;
MulticopterPositionControl::MulticopterPositionControl(bool vtol) :
SuperBlock(nullptr, "MPC"),
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers),
_vehicle_attitude_setpoint_pub(vtol ? ORB_ID(mc_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)),
_vel_x_deriv(this, "VELD"),
_vel_y_deriv(this, "VELD"),
_vel_z_deriv(this, "VELD")
{
parameters_update(true);
_failsafe_land_hysteresis.set_hysteresis_time_from(false, LOITER_TIME_BEFORE_DESCEND);
_tilt_limit_slew_rate.setSlewRate(.2f);
reset_setpoint_to_nan(_setpoint);
}
MulticopterPositionControl::~MulticopterPositionControl()
{
perf_free(_cycle_perf);
}
bool MulticopterPositionControl::init()
{
if (!_local_pos_sub.registerCallback()) {
PX4_ERR("vehicle_local_position callback registration failed!");
return false;
}
_time_stamp_last_loop = hrt_absolute_time();
ScheduleNow();
return true;
}
int MulticopterPositionControl::parameters_update(bool force)
{
// check for parameter updates
if (_parameter_update_sub.updated() || force) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
ModuleParams::updateParams();
SuperBlock::updateParams();
int num_changed = 0;
if (_param_sys_vehicle_resp.get() >= 0.f) {
// make it less sensitive at the lower end
float responsiveness = _param_sys_vehicle_resp.get() * _param_sys_vehicle_resp.get();
num_changed += _param_mpc_acc_hor.commit_no_notification(math::lerp(1.f, 15.f, responsiveness));
num_changed += _param_mpc_acc_hor_max.commit_no_notification(math::lerp(2.f, 15.f, responsiveness));
num_changed += _param_mpc_man_y_max.commit_no_notification(math::lerp(80.f, 450.f, responsiveness));
if (responsiveness > 0.6f) {
num_changed += _param_mpc_man_y_tau.commit_no_notification(0.f);
} else {
num_changed += _param_mpc_man_y_tau.commit_no_notification(math::lerp(0.5f, 0.f, responsiveness / 0.6f));
}
if (responsiveness < 0.5f) {
num_changed += _param_mpc_tiltmax_air.commit_no_notification(45.f);
} else {
num_changed += _param_mpc_tiltmax_air.commit_no_notification(math::min(MAX_SAFE_TILT_DEG, math::lerp(45.f, 70.f,
(responsiveness - 0.5f) * 2.f)));
}
num_changed += _param_mpc_acc_down_max.commit_no_notification(math::lerp(0.8f, 15.f, responsiveness));
num_changed += _param_mpc_acc_up_max.commit_no_notification(math::lerp(1.f, 15.f, responsiveness));
num_changed += _param_mpc_jerk_max.commit_no_notification(math::lerp(2.f, 50.f, responsiveness));
num_changed += _param_mpc_jerk_auto.commit_no_notification(math::lerp(1.f, 25.f, responsiveness));
}
if (_param_mpc_xy_vel_all.get() >= 0.f) {
float xy_vel = _param_mpc_xy_vel_all.get();
num_changed += _param_mpc_vel_manual.commit_no_notification(xy_vel);
num_changed += _param_mpc_xy_cruise.commit_no_notification(xy_vel);
num_changed += _param_mpc_xy_vel_max.commit_no_notification(xy_vel);
num_changed += _param_mpc_land_vel_xy.commit_no_notification(xy_vel * 0.75f);
}
if (_param_mpc_z_vel_all.get() >= 0.f) {
float z_vel = _param_mpc_z_vel_all.get();
num_changed += _param_mpc_z_vel_max_up.commit_no_notification(z_vel);
num_changed += _param_mpc_z_vel_max_dn.commit_no_notification(z_vel * 0.75f);
num_changed += _param_mpc_tko_speed.commit_no_notification(z_vel * 0.6f);
num_changed += _param_mpc_land_speed.commit_no_notification(z_vel * 0.5f);
}
if (num_changed > 0) {
param_notify_changes();
}
if (_param_mpc_tiltmax_air.get() > MAX_SAFE_TILT_DEG) {
_param_mpc_tiltmax_air.set(MAX_SAFE_TILT_DEG);
_param_mpc_tiltmax_air.commit();
mavlink_log_critical(&_mavlink_log_pub, "Tilt constrained to safe value");
}
if (_param_mpc_tiltmax_lnd.get() > _param_mpc_tiltmax_air.get()) {
_param_mpc_tiltmax_lnd.set(_param_mpc_tiltmax_air.get());
_param_mpc_tiltmax_lnd.commit();
mavlink_log_critical(&_mavlink_log_pub, "Land tilt has been constrained by max tilt");
}
_control.setPositionGains(Vector3f(_param_mpc_xy_p.get(), _param_mpc_xy_p.get(), _param_mpc_z_p.get()));
_control.setVelocityGains(
Vector3f(_param_mpc_xy_vel_p_acc.get(), _param_mpc_xy_vel_p_acc.get(), _param_mpc_z_vel_p_acc.get()),
Vector3f(_param_mpc_xy_vel_i_acc.get(), _param_mpc_xy_vel_i_acc.get(), _param_mpc_z_vel_i_acc.get()),
Vector3f(_param_mpc_xy_vel_d_acc.get(), _param_mpc_xy_vel_d_acc.get(), _param_mpc_z_vel_d_acc.get()));
// Check that the design parameters are inside the absolute maximum constraints
if (_param_mpc_xy_cruise.get() > _param_mpc_xy_vel_max.get()) {
_param_mpc_xy_cruise.set(_param_mpc_xy_vel_max.get());
_param_mpc_xy_cruise.commit();
mavlink_log_critical(&_mavlink_log_pub, "Cruise speed has been constrained by max speed");
}
if (_param_mpc_vel_manual.get() > _param_mpc_xy_vel_max.get()) {
_param_mpc_vel_manual.set(_param_mpc_xy_vel_max.get());
_param_mpc_vel_manual.commit();
mavlink_log_critical(&_mavlink_log_pub, "Manual speed has been constrained by max speed");
}
if (_param_mpc_thr_hover.get() > _param_mpc_thr_max.get() ||
_param_mpc_thr_hover.get() < _param_mpc_thr_min.get()) {
_param_mpc_thr_hover.set(math::constrain(_param_mpc_thr_hover.get(), _param_mpc_thr_min.get(),
_param_mpc_thr_max.get()));
_param_mpc_thr_hover.commit();
mavlink_log_critical(&_mavlink_log_pub, "Hover thrust has been constrained by min/max");
}
if (!_param_mpc_use_hte.get() || !_hover_thrust_initialized) {
_control.setHoverThrust(_param_mpc_thr_hover.get());
_hover_thrust_initialized = true;
}
// initialize vectors from params and enforce constraints
_param_mpc_tko_speed.set(math::min(_param_mpc_tko_speed.get(), _param_mpc_z_vel_max_up.get()));
_param_mpc_land_speed.set(math::min(_param_mpc_land_speed.get(), _param_mpc_z_vel_max_dn.get()));
_takeoff.setSpoolupTime(_param_mpc_spoolup_time.get());
_takeoff.setTakeoffRampTime(_param_mpc_tko_ramp_t.get());
_takeoff.generateInitialRampValue(_param_mpc_z_vel_p_acc.get());
}
return OK;
}
PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehicle_local_position_s &local_pos)
{
PositionControlStates states;
// only set position states if valid and finite
if (PX4_ISFINITE(local_pos.x) && PX4_ISFINITE(local_pos.y) && local_pos.xy_valid) {
states.position(0) = local_pos.x;
states.position(1) = local_pos.y;
} else {
states.position(0) = NAN;
states.position(1) = NAN;
}
if (PX4_ISFINITE(local_pos.z) && local_pos.z_valid) {
states.position(2) = local_pos.z;
} else {
states.position(2) = NAN;
}
if (PX4_ISFINITE(local_pos.vx) && PX4_ISFINITE(local_pos.vy) && local_pos.v_xy_valid) {
states.velocity(0) = local_pos.vx;
states.velocity(1) = local_pos.vy;
states.acceleration(0) = _vel_x_deriv.update(local_pos.vx);
states.acceleration(1) = _vel_y_deriv.update(local_pos.vy);
} else {
states.velocity(0) = NAN;
states.velocity(1) = NAN;
states.acceleration(0) = NAN;
states.acceleration(1) = NAN;
// reset derivatives to prevent acceleration spikes when regaining velocity
_vel_x_deriv.reset();
_vel_y_deriv.reset();
}
if (PX4_ISFINITE(local_pos.vz) && local_pos.v_z_valid) {
states.velocity(2) = local_pos.vz;
states.acceleration(2) = _vel_z_deriv.update(states.velocity(2));
} else {
states.velocity(2) = NAN;
states.acceleration(2) = NAN;
// reset derivative to prevent acceleration spikes when regaining velocity
_vel_z_deriv.reset();
}
states.yaw = local_pos.heading;
return states;
}
void MulticopterPositionControl::Run()
{
if (should_exit()) {
_local_pos_sub.unregisterCallback();
exit_and_cleanup();
return;
}
// reschedule backup
ScheduleDelayed(100_ms);
parameters_update(false);
perf_begin(_cycle_perf);
vehicle_local_position_s local_pos;
if (_local_pos_sub.update(&local_pos)) {
const hrt_abstime time_stamp_now = local_pos.timestamp;
const float dt = math::constrain(((time_stamp_now - _time_stamp_last_loop) * 1e-6f), 0.002f, 0.04f);
_time_stamp_last_loop = time_stamp_now;
// set _dt in controllib Block for BlockDerivative
setDt(dt);
const bool was_in_failsafe = _in_failsafe;
_in_failsafe = false;
_control_mode_sub.update(&_control_mode);
_vehicle_land_detected_sub.update(&_vehicle_land_detected);
if (_param_mpc_use_hte.get()) {
hover_thrust_estimate_s hte;
if (_hover_thrust_estimate_sub.update(&hte)) {
if (hte.valid) {
_control.updateHoverThrust(hte.hover_thrust);
}
}
}
PositionControlStates states{set_vehicle_states(local_pos)};
if (_control_mode.flag_control_acceleration_enabled || _control_mode.flag_control_climb_rate_enabled) {
_trajectory_setpoint_sub.update(&_setpoint);
// adjust existing (or older) setpoint with any EKF reset deltas
if (_setpoint.timestamp < local_pos.timestamp) {
if (local_pos.vxy_reset_counter != _vxy_reset_counter) {
_setpoint.vx += local_pos.delta_vxy[0];
_setpoint.vy += local_pos.delta_vxy[1];
}
if (local_pos.vz_reset_counter != _vz_reset_counter) {
_setpoint.vz += local_pos.delta_vz;
}
if (local_pos.xy_reset_counter != _xy_reset_counter) {
_setpoint.x += local_pos.delta_xy[0];
_setpoint.y += local_pos.delta_xy[1];
}
if (local_pos.z_reset_counter != _z_reset_counter) {
_setpoint.z += local_pos.delta_z;
}
if (local_pos.heading_reset_counter != _heading_reset_counter) {
_setpoint.yaw += local_pos.delta_heading;
}
}
// update vehicle constraints and handle smooth takeoff
_vehicle_constraints_sub.update(&_vehicle_constraints);
// fix to prevent the takeoff ramp to ramp to a too high value or get stuck because of NAN
// TODO: this should get obsolete once the takeoff limiting moves into the flight tasks
if (!PX4_ISFINITE(_vehicle_constraints.speed_up) || (_vehicle_constraints.speed_up > _param_mpc_z_vel_max_up.get())) {
_vehicle_constraints.speed_up = _param_mpc_z_vel_max_up.get();
}
if (_control_mode.flag_control_offboard_enabled) {
bool want_takeoff = _control_mode.flag_armed && _vehicle_land_detected.landed
&& hrt_elapsed_time(&_setpoint.timestamp) < 1_s;
if (want_takeoff && PX4_ISFINITE(_setpoint.z)
&& (_setpoint.z < states.position(2))) {
_vehicle_constraints.want_takeoff = true;
} else if (want_takeoff && PX4_ISFINITE(_setpoint.vz)
&& (_setpoint.vz < 0.f)) {
_vehicle_constraints.want_takeoff = true;
} else if (want_takeoff && PX4_ISFINITE(_setpoint.acceleration[2])
&& (_setpoint.acceleration[2] < 0.f)) {
_vehicle_constraints.want_takeoff = true;
} else {
_vehicle_constraints.want_takeoff = false;
}
// override with defaults
_vehicle_constraints.speed_xy = _param_mpc_xy_vel_max.get();
_vehicle_constraints.speed_up = _param_mpc_z_vel_max_up.get();
_vehicle_constraints.speed_down = _param_mpc_z_vel_max_dn.get();
}
// handle smooth takeoff
_takeoff.updateTakeoffState(_control_mode.flag_armed, _vehicle_land_detected.landed, _vehicle_constraints.want_takeoff,
_vehicle_constraints.speed_up, false, time_stamp_now);
const bool not_taken_off = (_takeoff.getTakeoffState() < TakeoffState::rampup);
const bool flying = (_takeoff.getTakeoffState() >= TakeoffState::flight);
const bool flying_but_ground_contact = (flying && _vehicle_land_detected.ground_contact);
// make sure takeoff ramp is not amended by acceleration feed-forward
if (!flying) {
_setpoint.acceleration[2] = NAN;
}
if (not_taken_off || flying_but_ground_contact) {
// we are not flying yet and need to avoid any corrections
reset_setpoint_to_nan(_setpoint);
Vector3f(0.f, 0.f, 100.f).copyTo(_setpoint.acceleration); // High downwards acceleration to make sure there's no thrust
// prevent any integrator windup
_control.resetIntegral();
}
// limit tilt during takeoff ramupup
const float tilt_limit_deg = (_takeoff.getTakeoffState() < TakeoffState::flight)
? _param_mpc_tiltmax_lnd.get() : _param_mpc_tiltmax_air.get();
_control.setTiltLimit(_tilt_limit_slew_rate.update(math::radians(tilt_limit_deg), dt));
const float speed_up = _takeoff.updateRamp(dt,
PX4_ISFINITE(_vehicle_constraints.speed_up) ? _vehicle_constraints.speed_up : _param_mpc_z_vel_max_up.get());
const float speed_down = PX4_ISFINITE(_vehicle_constraints.speed_down) ? _vehicle_constraints.speed_down :
_param_mpc_z_vel_max_dn.get();
const float speed_horizontal = PX4_ISFINITE(_vehicle_constraints.speed_xy) ? _vehicle_constraints.speed_xy :
_param_mpc_xy_vel_max.get();
// Allow ramping from zero thrust on takeoff
const float minimum_thrust = flying ? _param_mpc_thr_min.get() : 0.f;
_control.setThrustLimits(minimum_thrust, _param_mpc_thr_max.get());
_control.setVelocityLimits(
math::constrain(speed_horizontal, 0.f, _param_mpc_xy_vel_max.get()),
math::min(speed_up, _param_mpc_z_vel_max_up.get()), // takeoff ramp starts with negative velocity limit
math::constrain(speed_down, 0.f, _param_mpc_z_vel_max_dn.get()));
_control.setInputSetpoint(_setpoint);
// update states
if (PX4_ISFINITE(_setpoint.vz) && (fabsf(_setpoint.vz) > FLT_EPSILON)
&& PX4_ISFINITE(local_pos.z_deriv) && local_pos.z_valid && local_pos.v_z_valid) {
// A change in velocity is demanded. Set velocity to the derivative of position
// because it has less bias but blend it in across the landing speed range
// < MPC_LAND_SPEED: ramp up using altitude derivative without a step
// >= MPC_LAND_SPEED: use altitude derivative
float weighting = fminf(fabsf(_setpoint.vz) / _param_mpc_land_speed.get(), 1.f);
states.velocity(2) = local_pos.z_deriv * weighting + local_pos.vz * (1.f - weighting);
}
_control.setState(states);
// Run position control
if (_control.update(dt)) {
_failsafe_land_hysteresis.set_state_and_update(false, time_stamp_now);
} else {
// Failsafe
if ((time_stamp_now - _last_warn) > 2_s) {
PX4_WARN("invalid setpoints");
_last_warn = time_stamp_now;
}
vehicle_local_position_setpoint_s failsafe_setpoint{};
failsafe(time_stamp_now, failsafe_setpoint, states, !was_in_failsafe);
// reset constraints
_vehicle_constraints = {0, NAN, NAN, NAN, false, {}};
_control.setInputSetpoint(failsafe_setpoint);
_control.setVelocityLimits(_param_mpc_xy_vel_max.get(), _param_mpc_z_vel_max_up.get(), _param_mpc_z_vel_max_dn.get());
_control.update(dt);
}
// Publish internal position control setpoints
// on top of the input/feed-forward setpoints these containt the PID corrections
// This message is used by other modules (such as Landdetector) to determine vehicle intention.
vehicle_local_position_setpoint_s local_pos_sp{};
_control.getLocalPositionSetpoint(local_pos_sp);
local_pos_sp.timestamp = hrt_absolute_time();
_local_pos_sp_pub.publish(local_pos_sp);
// Publish attitude setpoint output
vehicle_attitude_setpoint_s attitude_setpoint{};
_control.getAttitudeSetpoint(attitude_setpoint);
attitude_setpoint.timestamp = hrt_absolute_time();
_vehicle_attitude_setpoint_pub.publish(attitude_setpoint);
} else {
// an update is necessary here because otherwise the takeoff state doesn't get skiped with non-altitude-controlled modes
_takeoff.updateTakeoffState(_control_mode.flag_armed, _vehicle_land_detected.landed, false, 10.f, true, time_stamp_now);
}
// Publish takeoff status
const uint8_t takeoff_state = static_cast<uint8_t>(_takeoff.getTakeoffState());
if (takeoff_state != _takeoff_status_pub.get().takeoff_state
|| !isEqualF(_tilt_limit_slew_rate.getState(), _takeoff_status_pub.get().tilt_limit)) {
_takeoff_status_pub.get().takeoff_state = takeoff_state;
_takeoff_status_pub.get().tilt_limit = _tilt_limit_slew_rate.getState();
_takeoff_status_pub.get().timestamp = hrt_absolute_time();
_takeoff_status_pub.update();
}
// save latest reset counters
_vxy_reset_counter = local_pos.vxy_reset_counter;
_vz_reset_counter = local_pos.vz_reset_counter;
_xy_reset_counter = local_pos.xy_reset_counter;
_z_reset_counter = local_pos.z_reset_counter;
_heading_reset_counter = local_pos.heading_reset_counter;
}
perf_end(_cycle_perf);
}
void MulticopterPositionControl::failsafe(const hrt_abstime &now, vehicle_local_position_setpoint_s &setpoint,
const PositionControlStates &states, bool warn)
{
// do not warn while we are disarmed, as we might not have valid setpoints yet
if (!_control_mode.flag_armed) {
warn = false;
}
// Only react after a short delay
_failsafe_land_hysteresis.set_state_and_update(true, now);
if (_failsafe_land_hysteresis.get_state()) {
reset_setpoint_to_nan(setpoint);
if (PX4_ISFINITE(states.velocity(0)) && PX4_ISFINITE(states.velocity(1))) {
// don't move along xy
setpoint.vx = setpoint.vy = 0.f;
if (warn) {
PX4_WARN("Failsafe: stop and wait");
}
} else {
// descend with land speed since we can't stop
setpoint.acceleration[0] = setpoint.acceleration[1] = 0.f;
setpoint.vz = _param_mpc_land_speed.get();
if (warn) {
PX4_WARN("Failsafe: blind land");
}
}
if (PX4_ISFINITE(states.velocity(2))) {
// don't move along z if we can stop in all dimensions
if (!PX4_ISFINITE(setpoint.vz)) {
setpoint.vz = 0.f;
}
} else {
// emergency descend with a bit below hover thrust
setpoint.vz = NAN;
setpoint.acceleration[2] = .3f;
if (warn) {
PX4_WARN("Failsafe: blind descend");
}
}
_in_failsafe = true;
}
}
void MulticopterPositionControl::reset_setpoint_to_nan(vehicle_local_position_setpoint_s &setpoint)
{
setpoint.x = setpoint.y = setpoint.z = NAN;
setpoint.vx = setpoint.vy = setpoint.vz = NAN;
setpoint.yaw = setpoint.yawspeed = NAN;
setpoint.acceleration[0] = setpoint.acceleration[1] = setpoint.acceleration[2] = NAN;
setpoint.thrust[0] = setpoint.thrust[1] = setpoint.thrust[2] = NAN;
}
int MulticopterPositionControl::task_spawn(int argc, char *argv[])
{
bool vtol = false;
if (argc > 1) {
if (strcmp(argv[1], "vtol") == 0) {
vtol = true;
}
}
MulticopterPositionControl *instance = new MulticopterPositionControl(vtol);
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance;
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
int MulticopterPositionControl::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int MulticopterPositionControl::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
The controller has two loops: a P loop for position error and a PID loop for velocity error.
Output of the velocity controller is thrust vector that is split to thrust direction
(i.e. rotation matrix for multicopter orientation) and thrust scalar (i.e. multicopter thrust itself).
The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and
logging.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("mc_pos_control", "controller");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_ARG("vtol", "VTOL mode", true);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
extern "C" __EXPORT int mc_pos_control_main(int argc, char *argv[])
{
return MulticopterPositionControl::main(argc, argv);
}