-
Notifications
You must be signed in to change notification settings - Fork 1.1k
/
guidance_h.c
636 lines (543 loc) · 20.2 KB
/
guidance_h.c
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
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
/*
* Copyright (C) 2008-2009 Antoine Drouin <poinix@gmail.com>
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
/** @file firmwares/rotorcraft/guidance/guidance_h.c
* Horizontal guidance for rotorcrafts.
*
*/
#include "generated/airframe.h"
#include "firmwares/rotorcraft/guidance/guidance_hybrid.h"
#include "firmwares/rotorcraft/guidance/guidance_h.h"
#include "firmwares/rotorcraft/guidance/guidance_flip.h"
#include "firmwares/rotorcraft/guidance/guidance_module.h"
#include "firmwares/rotorcraft/stabilization.h"
#include "firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.h"
#include "firmwares/rotorcraft/navigation.h"
#include "modules/radio_control/radio_control.h"
#include "firmwares/rotorcraft/stabilization/stabilization_none.h"
#include "firmwares/rotorcraft/stabilization/stabilization_rate.h"
#include "firmwares/rotorcraft/stabilization/stabilization_attitude.h"
/* for guidance_v.thrust_coeff */
#include "firmwares/rotorcraft/guidance/guidance_v.h"
#include "state.h"
PRINT_CONFIG_VAR(GUIDANCE_H_USE_REF)
PRINT_CONFIG_VAR(GUIDANCE_H_USE_SPEED_REF)
struct HorizontalGuidance guidance_h;
int32_t transition_percentage;
/** horizontal guidance command.
* In north/east with #INT32_ANGLE_FRAC
*/
struct StabilizationSetpoint guidance_h_cmd;
static void guidance_h_update_reference(void);
static inline void transition_run(bool to_forward);
static void read_rc_setpoint_speed_i(struct Int32Vect2 *speed_sp, bool in_flight);
#if PERIODIC_TELEMETRY
#include "modules/datalink/telemetry.h"
static void send_gh(struct transport_tx *trans, struct link_device *dev)
{
struct NedCoor_i *pos = stateGetPositionNed_i();
pprz_msg_send_GUIDANCE_H_INT(trans, dev, AC_ID,
&guidance_h.sp.pos.x, &guidance_h.sp.pos.y,
&guidance_h.ref.pos.x, &guidance_h.ref.pos.y,
&(pos->x), &(pos->y));
}
static void send_href(struct transport_tx *trans, struct link_device *dev)
{
pprz_msg_send_GUIDANCE_H_REF_INT(trans, dev, AC_ID,
&guidance_h.sp.pos.x, &guidance_h.ref.pos.x,
&guidance_h.sp.speed.x, &guidance_h.ref.speed.x,
&guidance_h.ref.accel.x,
&guidance_h.sp.pos.y, &guidance_h.ref.pos.y,
&guidance_h.sp.speed.y, &guidance_h.ref.speed.y,
&guidance_h.ref.accel.y);
}
#if defined(COMMAND_ROLL) && defined(COMMAND_PITCH) && defined(COMMAND_YAW)
static void send_tune_hover(struct transport_tx *trans, struct link_device *dev)
{
pprz_msg_send_ROTORCRAFT_TUNE_HOVER(trans, dev, AC_ID,
&radio_control.values[RADIO_ROLL],
&radio_control.values[RADIO_PITCH],
&radio_control.values[RADIO_YAW],
&stabilization_cmd[COMMAND_ROLL],
&stabilization_cmd[COMMAND_PITCH],
&stabilization_cmd[COMMAND_YAW],
&stabilization_cmd[COMMAND_THRUST],
&(stateGetNedToBodyEulers_i()->phi),
&(stateGetNedToBodyEulers_i()->theta),
&(stateGetNedToBodyEulers_i()->psi));
}
#else
static void send_tune_hover(struct transport_tx *trans UNUSED, struct link_device *dev UNUSED) {}
#endif
#endif
void guidance_h_init(void)
{
guidance_h.mode = GUIDANCE_H_MODE_KILL;
guidance_h.use_ref = GUIDANCE_H_USE_REF;
INT_VECT2_ZERO(guidance_h.sp.pos);
FLOAT_EULERS_ZERO(guidance_h.rc_sp);
guidance_h.sp.heading = 0.0;
guidance_h.sp.heading_rate = 0.0;
guidance_h.sp.h_mask = GUIDANCE_H_SP_POS;
guidance_h.sp.yaw_mask = GUIDANCE_H_SP_YAW;
transition_percentage = 0;
transition_theta_offset = 0;
gh_ref_init();
#if GUIDANCE_H_MODE_MODULE_SETTING == GUIDANCE_H_MODE_MODULE
guidance_h_module_init();
#endif
#if PERIODIC_TELEMETRY
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_GUIDANCE_H_INT, send_gh);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_GUIDANCE_H_REF_INT, send_href);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_ROTORCRAFT_TUNE_HOVER, send_tune_hover);
#endif
}
static inline void reset_guidance_reference_from_current_position(void)
{
VECT2_COPY(guidance_h.ref.pos, *stateGetPositionNed_i());
VECT2_COPY(guidance_h.ref.speed, *stateGetSpeedNed_i());
struct FloatVect2 ref_speed;
ref_speed.x = SPEED_FLOAT_OF_BFP(guidance_h.ref.speed.x);
ref_speed.y = SPEED_FLOAT_OF_BFP(guidance_h.ref.speed.y);
INT_VECT2_ZERO(guidance_h.ref.accel);
struct FloatVect2 ref_accel;
FLOAT_VECT2_ZERO(ref_accel);
gh_set_ref(guidance_h.ref.pos, ref_speed, ref_accel);
}
void guidance_h_mode_changed(uint8_t new_mode)
{
if (new_mode == guidance_h.mode) {
return;
}
switch (new_mode) {
case GUIDANCE_H_MODE_RC_DIRECT:
stabilization_none_enter();
break;
#if USE_STABILIZATION_RATE
case GUIDANCE_H_MODE_RATE:
stabilization_rate_enter();
break;
#endif
case GUIDANCE_H_MODE_CARE_FREE:
stabilization_attitude_reset_care_free_heading();
/* Falls through. */
case GUIDANCE_H_MODE_FORWARD:
case GUIDANCE_H_MODE_ATTITUDE:
#if NO_ATTITUDE_RESET_ON_MODE_CHANGE
/* reset attitude stabilization if previous mode was not using it */
if (guidance_h.mode == GUIDANCE_H_MODE_KILL ||
guidance_h.mode == GUIDANCE_H_MODE_RATE ||
guidance_h.mode == GUIDANCE_H_MODE_RC_DIRECT)
#endif
stabilization_attitude_enter();
break;
case GUIDANCE_H_MODE_GUIDED:
case GUIDANCE_H_MODE_HOVER:
guidance_h_hover_enter();
#if NO_ATTITUDE_RESET_ON_MODE_CHANGE
/* reset attitude stabilization if previous mode was not using it */
if (guidance_h.mode == GUIDANCE_H_MODE_KILL ||
guidance_h.mode == GUIDANCE_H_MODE_RATE ||
guidance_h.mode == GUIDANCE_H_MODE_RC_DIRECT)
#endif
stabilization_attitude_enter();
break;
#if GUIDANCE_H_MODE_MODULE_SETTING == GUIDANCE_H_MODE_MODULE
case GUIDANCE_H_MODE_MODULE:
guidance_h_module_enter();
break;
#endif
case GUIDANCE_H_MODE_NAV:
guidance_h_nav_enter();
#if NO_ATTITUDE_RESET_ON_MODE_CHANGE
/* reset attitude stabilization if previous mode was not using it */
if (guidance_h.mode == GUIDANCE_H_MODE_KILL ||
guidance_h.mode == GUIDANCE_H_MODE_RATE ||
guidance_h.mode == GUIDANCE_H_MODE_RC_DIRECT)
#endif
stabilization_attitude_enter();
break;
case GUIDANCE_H_MODE_FLIP:
guidance_flip_enter();
break;
default:
break;
}
guidance_h.mode = new_mode;
}
void guidance_h_read_rc(bool in_flight)
{
switch (guidance_h.mode) {
case GUIDANCE_H_MODE_RC_DIRECT:
stabilization_none_read_rc();
break;
#if USE_STABILIZATION_RATE
case GUIDANCE_H_MODE_RATE:
#if SWITCH_STICKS_FOR_RATE_CONTROL
stabilization_rate_read_rc_switched_sticks();
#else
stabilization_rate_read_rc();
#endif
break;
#endif
case GUIDANCE_H_MODE_CARE_FREE:
stabilization_attitude_read_rc(in_flight, TRUE, FALSE);
break;
case GUIDANCE_H_MODE_FORWARD:
stabilization_attitude_read_rc(in_flight, FALSE, TRUE);
break;
case GUIDANCE_H_MODE_ATTITUDE:
stabilization_attitude_read_rc(in_flight, FALSE, FALSE);
break;
case GUIDANCE_H_MODE_HOVER:
stabilization_attitude_read_rc_setpoint_eulers_f(&guidance_h.rc_sp, in_flight, FALSE, FALSE);
#if GUIDANCE_H_USE_SPEED_REF
read_rc_setpoint_speed_i(&guidance_h.sp.speed, in_flight);
/* enable x,y velocity setpoints */
guidance_h.sp.h_mask = GUIDANCE_H_SP_SPEED;
#endif
break;
#if GUIDANCE_H_MODE_MODULE_SETTING == GUIDANCE_H_MODE_MODULE
case GUIDANCE_H_MODE_MODULE:
guidance_h_module_read_rc();
break;
#endif
case GUIDANCE_H_MODE_NAV:
if (radio_control.status == RC_OK) {
stabilization_attitude_read_rc_setpoint_eulers_f(&guidance_h.rc_sp, in_flight, FALSE, FALSE);
} else {
FLOAT_EULERS_ZERO(guidance_h.rc_sp);
}
break;
case GUIDANCE_H_MODE_FLIP:
stabilization_attitude_read_rc(in_flight, FALSE, FALSE);
break;
default:
break;
}
}
void guidance_h_run(bool in_flight)
{
switch (guidance_h.mode) {
case GUIDANCE_H_MODE_RC_DIRECT:
stabilization_none_run(in_flight);
break;
#if USE_STABILIZATION_RATE
case GUIDANCE_H_MODE_RATE:
stabilization_rate_run(in_flight);
break;
#endif
case GUIDANCE_H_MODE_FORWARD:
if (transition_percentage < (100 << INT32_PERCENTAGE_FRAC)) {
transition_run(true);
}
/* Falls through. */
case GUIDANCE_H_MODE_CARE_FREE:
case GUIDANCE_H_MODE_ATTITUDE:
if ((!(guidance_h.mode == GUIDANCE_H_MODE_FORWARD)) && transition_percentage > 0) {
transition_run(false);
}
stabilization_attitude_run(in_flight);
#if (STABILIZATION_FILTER_CMD_ROLL_PITCH || STABILIZATION_FILTER_CMD_YAW)
if (in_flight) {
stabilization_filter_commands();
}
#endif
break;
case GUIDANCE_H_MODE_HOVER:
/* set psi command from RC */
guidance_h.sp.heading = guidance_h.rc_sp.psi;
/* fall trough to GUIDED to update ref, run traj and set final attitude setpoint */
/* Falls through. */
case GUIDANCE_H_MODE_GUIDED:
guidance_h_guided_run(in_flight);
break;
case GUIDANCE_H_MODE_NAV:
guidance_h_from_nav(in_flight);
break;
#if GUIDANCE_H_MODE_MODULE_SETTING == GUIDANCE_H_MODE_MODULE
case GUIDANCE_H_MODE_MODULE:
guidance_h_module_run(in_flight);
break;
#endif
case GUIDANCE_H_MODE_FLIP:
guidance_flip_run();
break;
default:
break;
}
}
static void guidance_h_update_reference(void)
{
/* compute reference even if usage temporarily disabled via guidance_h_use_ref */
#if GUIDANCE_H_USE_REF
if (guidance_h.sp.h_mask == GUIDANCE_H_SP_ACCEL) {
struct FloatVect2 sp_accel_local;
sp_accel_local.x = ACCEL_FLOAT_OF_BFP(guidance_h.sp.accel.x);
sp_accel_local.y = ACCEL_FLOAT_OF_BFP(guidance_h.sp.accel.y);
gh_update_ref_from_accel_sp(sp_accel_local);
}
else if (guidance_h.sp.h_mask == GUIDANCE_H_SP_SPEED) {
struct FloatVect2 sp_speed;
sp_speed.x = SPEED_FLOAT_OF_BFP(guidance_h.sp.speed.x);
sp_speed.y = SPEED_FLOAT_OF_BFP(guidance_h.sp.speed.y);
gh_update_ref_from_speed_sp(sp_speed);
} else {
gh_update_ref_from_pos_sp(guidance_h.sp.pos);
}
#endif
/* either use the reference or simply copy the pos setpoint */
if (guidance_h.use_ref) {
/* convert our reference to generic representation */
INT32_VECT2_RSHIFT(guidance_h.ref.pos, gh_ref.pos, (GH_POS_REF_FRAC - INT32_POS_FRAC));
guidance_h.ref.speed.x = SPEED_BFP_OF_REAL(gh_ref.speed.x);
guidance_h.ref.speed.y = SPEED_BFP_OF_REAL(gh_ref.speed.y);
guidance_h.ref.accel.x = ACCEL_BFP_OF_REAL(gh_ref.accel.x);
guidance_h.ref.accel.y = ACCEL_BFP_OF_REAL(gh_ref.accel.y);
} else {
switch (nav.setpoint_mode) {
case NAV_SETPOINT_MODE_SPEED:
guidance_h.ref.pos.x = stateGetPositionNed_i()->x;
guidance_h.ref.pos.y = stateGetPositionNed_i()->y;
guidance_h.ref.speed.x = guidance_h.sp.speed.x;
guidance_h.ref.speed.y = guidance_h.sp.speed.y;
guidance_h.ref.accel.x = 0;
guidance_h.ref.accel.y = 0;
break;
case NAV_SETPOINT_MODE_ACCEL:
guidance_h.ref.pos.x = stateGetPositionNed_i()->x;
guidance_h.ref.pos.y = stateGetPositionNed_i()->y;
guidance_h.ref.speed.x = stateGetSpeedNed_i()->x;
guidance_h.ref.speed.y = stateGetSpeedNed_i()->y;
guidance_h.ref.accel.x = guidance_h.sp.accel.x;
guidance_h.ref.accel.y = guidance_h.sp.accel.y;
break;
case NAV_SETPOINT_MODE_POS:
default: // Fallback is guidance by pos
VECT2_COPY(guidance_h.ref.pos, guidance_h.sp.pos);
INT_VECT2_ZERO(guidance_h.ref.speed);
INT_VECT2_ZERO(guidance_h.ref.accel);
break;
}
}
#if GUIDANCE_H_USE_SPEED_REF
if (guidance_h.mode == GUIDANCE_H_MODE_HOVER) {
VECT2_COPY(guidance_h.sp.pos, guidance_h.ref.pos); // for display only
}
#endif
/* update heading setpoint from rate */
if (guidance_h.sp.yaw_mask == GUIDANCE_H_SP_YAW_RATE) {
guidance_h.sp.heading += guidance_h.sp.heading_rate / PERIODIC_FREQUENCY;
FLOAT_ANGLE_NORMALIZE(guidance_h.sp.heading);
}
}
void guidance_h_hover_enter(void)
{
/* reset speed setting */
guidance_h.sp.speed.x = 0;
guidance_h.sp.speed.y = 0;
/* set horizontal setpoint to current position */
guidance_h_set_pos(
stateGetPositionNed_f()->x,
stateGetPositionNed_f()->y);
/* reset guidance reference */
reset_guidance_reference_from_current_position();
/* set guidance to current heading and position */
guidance_h.rc_sp.psi = stateGetNedToBodyEulers_f()->psi;
guidance_h_set_heading(stateGetNedToBodyEulers_f()->psi);
/* call specific implementation */
guidance_h_run_enter();
}
void guidance_h_nav_enter(void)
{
/* horizontal position setpoint from navigation/flightplan */
guidance_h_set_pos(nav.carrot.y, nav.carrot.x);
reset_guidance_reference_from_current_position();
/* call specific implementation */
guidance_h_run_enter();
guidance_h_set_heading(nav.heading);
}
void guidance_h_from_nav(bool in_flight)
{
if (!in_flight) {
guidance_h_nav_enter();
}
if (nav.horizontal_mode == NAV_HORIZONTAL_MODE_NONE) {
return; // don't call guidance nor stabilization
} else if (nav.horizontal_mode == NAV_HORIZONTAL_MODE_ATTITUDE) {
if (nav.setpoint_mode == NAV_SETPOINT_MODE_QUAT) {
// directly apply quat setpoint
struct Int32Quat quat_i;
QUAT_BFP_OF_REAL(quat_i, nav.quat);
stabilization_attitude_set_quat_setpoint_i(&quat_i);
stabilization_attitude_run(in_flight);
}
else {
// it should be nav.setpoint_mode == NAV_SETPOINT_MODE_ATTITUDE
// TODO error handling ?
struct Int32Eulers sp_cmd_i;
sp_cmd_i.phi = ANGLE_BFP_OF_REAL(nav.roll);
sp_cmd_i.theta = ANGLE_BFP_OF_REAL(nav.pitch);
sp_cmd_i.psi = ANGLE_BFP_OF_REAL(nav.heading);
stabilization_attitude_set_rpy_setpoint_i(&sp_cmd_i);
stabilization_attitude_run(in_flight);
}
} else if (nav.horizontal_mode == NAV_HORIZONTAL_MODE_GUIDED) {
guidance_h_guided_run(in_flight);
} else {
// update carrot for GCS display and convert ENU float -> NED int
// even if sp is changed later
guidance_h.sp.pos.x = POS_BFP_OF_REAL(nav.carrot.y);
guidance_h.sp.pos.y = POS_BFP_OF_REAL(nav.carrot.x);
switch (nav.setpoint_mode) {
case NAV_SETPOINT_MODE_POS:
guidance_h_set_pos(nav.carrot.y, nav.carrot.x); // nav pos is in ENU frame, convert to NED
guidance_h_update_reference();
guidance_h_set_heading(nav.heading);
guidance_h_cmd = guidance_h_run_pos(in_flight, &guidance_h);
break;
case NAV_SETPOINT_MODE_SPEED:
guidance_h_set_vel(nav.speed.y, nav.speed.x); // nav speed is in ENU frame, convert to NED
guidance_h_update_reference();
guidance_h_set_heading(nav.heading);
guidance_h_cmd = guidance_h_run_speed(in_flight, &guidance_h);
break;
case NAV_SETPOINT_MODE_ACCEL:
guidance_h_set_acc(nav.accel.y, nav.accel.x); // nav acc is in ENU frame, convert to NED
guidance_h_update_reference();
guidance_h_set_heading(nav.heading);
guidance_h_cmd = guidance_h_run_accel(in_flight, &guidance_h);
break;
default:
// nothing to do for other cases at the moment
break;
}
/* set final attitude setpoint */
stabilization_attitude_set_stab_sp(&guidance_h_cmd);
stabilization_attitude_run(in_flight);
}
}
static inline void transition_run(bool to_forward)
{
if (to_forward) {
//Add 0.00625%
transition_percentage += 1 << (INT32_PERCENTAGE_FRAC - 4);
} else {
//Subtract 0.00625%
transition_percentage -= 1 << (INT32_PERCENTAGE_FRAC - 4);
}
#ifdef TRANSITION_MAX_OFFSET
const int32_t max_offset = ANGLE_BFP_OF_REAL(TRANSITION_MAX_OFFSET);
transition_theta_offset = INT_MULT_RSHIFT((transition_percentage << (INT32_ANGLE_FRAC - INT32_PERCENTAGE_FRAC)) / 100,
max_offset, INT32_ANGLE_FRAC);
#endif
}
/// read speed setpoint from RC
static void read_rc_setpoint_speed_i(struct Int32Vect2 *speed_sp, bool in_flight)
{
if (in_flight) {
// negative pitch is forward
int64_t rc_x = -radio_control.values[RADIO_PITCH];
int64_t rc_y = radio_control.values[RADIO_ROLL];
DeadBand(rc_x, MAX_PPRZ / 20);
DeadBand(rc_y, MAX_PPRZ / 20);
// convert input from MAX_PPRZ range to SPEED_BFP
int32_t max_speed = SPEED_BFP_OF_REAL(GUIDANCE_H_REF_MAX_SPEED);
/// @todo calc proper scale while making sure a division by zero can't occur
//int32_t rc_norm = sqrtf(rc_x * rc_x + rc_y * rc_y);
//int32_t max_pprz = rc_norm * MAX_PPRZ / Max(abs(rc_x), abs(rc_y);
rc_x = rc_x * max_speed / MAX_PPRZ;
rc_y = rc_y * max_speed / MAX_PPRZ;
/* Rotate from body to NED frame by negative psi angle */
int32_t psi = -stateGetNedToBodyEulers_i()->psi;
int32_t s_psi, c_psi;
PPRZ_ITRIG_SIN(s_psi, psi);
PPRZ_ITRIG_COS(c_psi, psi);
speed_sp->x = (int32_t)(((int64_t)c_psi * rc_x + (int64_t)s_psi * rc_y) >> INT32_TRIG_FRAC);
speed_sp->y = (int32_t)((-(int64_t)s_psi * rc_x + (int64_t)c_psi * rc_y) >> INT32_TRIG_FRAC);
} else {
speed_sp->x = 0;
speed_sp->y = 0;
}
}
void guidance_h_guided_run(bool in_flight)
{
/* guidance_h.sp.pos and guidance_h.sp.heading need to be set from external source */
if (!in_flight) {
guidance_h_hover_enter();
}
guidance_h_update_reference();
guidance_h_cmd = guidance_h_run_pos(in_flight, &guidance_h);
/* set final attitude setpoint */
stabilization_attitude_set_stab_sp(&guidance_h_cmd);
stabilization_attitude_run(in_flight);
}
void guidance_h_set_pos(float x, float y)
{
if (guidance_h.sp.h_mask != GUIDANCE_H_SP_POS) {
reset_guidance_reference_from_current_position();
}
guidance_h.sp.h_mask = GUIDANCE_H_SP_POS;
guidance_h.sp.pos.x = POS_BFP_OF_REAL(x);
guidance_h.sp.pos.y = POS_BFP_OF_REAL(y);
}
void guidance_h_set_heading(float heading)
{
guidance_h.sp.yaw_mask = GUIDANCE_H_SP_YAW;
guidance_h.sp.heading = heading;
FLOAT_ANGLE_NORMALIZE(guidance_h.sp.heading);
}
void guidance_h_set_body_vel(float vx, float vy)
{
float psi = stateGetNedToBodyEulers_f()->psi;
float newvx = cosf(-psi) * vx + sinf(-psi) * vy;
float newvy = -sinf(-psi) * vx + cosf(-psi) * vy;
guidance_h_set_vel(newvx, newvy);
}
void guidance_h_set_vel(float vx, float vy)
{
if (guidance_h.sp.h_mask != GUIDANCE_H_SP_SPEED) {
reset_guidance_reference_from_current_position();
}
guidance_h.sp.h_mask = GUIDANCE_H_SP_SPEED;
guidance_h.sp.speed.x = SPEED_BFP_OF_REAL(vx);
guidance_h.sp.speed.y = SPEED_BFP_OF_REAL(vy);
}
void guidance_h_set_body_acc(float ax, float ay)
{
float psi = stateGetNedToBodyEulers_f()->psi;
float newax = cosf(-psi) * ax + sinf(-psi) * ay;
float neway = -sinf(-psi) * ax + cosf(-psi) * ay;
guidance_h_set_acc(newax, neway);
}
void guidance_h_set_acc(float ax, float ay)
{
if (guidance_h.sp.h_mask != GUIDANCE_H_SP_ACCEL) {
reset_guidance_reference_from_current_position();
}
guidance_h.sp.h_mask = GUIDANCE_H_SP_ACCEL;
guidance_h.sp.accel.x = ACCEL_BFP_OF_REAL(ax);
guidance_h.sp.accel.y = ACCEL_BFP_OF_REAL(ay);
}
void guidance_h_set_heading_rate(float rate)
{
guidance_h.sp.yaw_mask = GUIDANCE_H_SP_YAW_RATE;
guidance_h.sp.heading_rate = rate;
}