Paparazzi UAS  v5.10_stable-5-g83a0da5-dirty
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
navigation.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008-2009 Antoine Drouin <poinix@gmail.com>
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  */
21 
29 #define NAV_C
30 
32 
33 #include "pprz_debug.h"
34 #include "subsystems/gps.h" // needed by auto_nav from the flight plan
35 #include "subsystems/ins.h"
36 #include "state.h"
37 
39 #include "generated/modules.h"
40 #include "generated/flight_plan.h"
41 
42 /* for default GUIDANCE_H_USE_REF */
44 
45 #include "math/pprz_algebra_int.h"
46 
48 #include "pprzlink/messages.h"
49 #include "mcu_periph/uart.h"
50 
53 
55 
57 
59 #ifndef FAILSAFE_MODE_DISTANCE
60 #define FAILSAFE_MODE_DISTANCE (1.5*MAX_DIST_FROM_HOME)
61 #endif
62 
63 const float max_dist_from_home = MAX_DIST_FROM_HOME;
64 const float max_dist2_from_home = MAX_DIST_FROM_HOME * MAX_DIST_FROM_HOME;
68 
69 bool exception_flag[10] = {0}; //exception flags that can be used in the flight plan
70 
72 
74 struct EnuCoor_i nav_segment_start, nav_segment_end;
77 
80 
82 
86 float nav_radius;
88 
90 #ifndef DEFAULT_CIRCLE_RADIUS
91 #define DEFAULT_CIRCLE_RADIUS 5.
92 #endif
93 
94 #ifndef NAV_CLIMB_VSPEED
95 #define NAV_CLIMB_VSPEED 0.5
96 #endif
97 
98 #ifndef NAV_DESCEND_VSPEED
99 #define NAV_DESCEND_VSPEED -0.8
100 #endif
101 
106 
107 static inline void nav_set_altitude(void);
108 
109 #define CLOSE_TO_WAYPOINT (15 << INT32_POS_FRAC)
110 #define CARROT_DIST (12 << INT32_POS_FRAC)
111 
113 #ifndef ARRIVED_AT_WAYPOINT
114 #define ARRIVED_AT_WAYPOINT 3.0
115 #endif
116 
117 #if PERIODIC_TELEMETRY
119 
121 {
122  exception_flag[flag_num] = 1;
123 }
124 
125 static void send_nav_status(struct transport_tx *trans, struct link_device *dev)
126 {
127  float dist_home = sqrtf(dist2_to_home);
128  float dist_wp = sqrtf(dist2_to_wp);
129  pprz_msg_send_ROTORCRAFT_NAV_STATUS(trans, dev, AC_ID,
131  &dist_home, &dist_wp,
132  &nav_block, &nav_stage,
133  &horizontal_mode);
135  float sx = POS_FLOAT_OF_BFP(nav_segment_start.x);
136  float sy = POS_FLOAT_OF_BFP(nav_segment_start.y);
137  float ex = POS_FLOAT_OF_BFP(nav_segment_end.x);
138  float ey = POS_FLOAT_OF_BFP(nav_segment_end.y);
139  pprz_msg_send_SEGMENT(trans, dev, AC_ID, &sx, &sy, &ex, &ey);
140  } else if (horizontal_mode == HORIZONTAL_MODE_CIRCLE) {
144  pprz_msg_send_CIRCLE(trans, dev, AC_ID, &cx, &cy, &r);
145  }
146 }
147 
148 static void send_wp_moved(struct transport_tx *trans, struct link_device *dev)
149 {
150  static uint8_t i;
151  i++;
152  if (i >= nb_waypoint) { i = 0; }
153  pprz_msg_send_WP_MOVED_ENU(trans, dev, AC_ID,
154  &i,
155  &(waypoints[i].enu_i.x),
156  &(waypoints[i].enu_i.y),
157  &(waypoints[i].enu_i.z));
158 }
159 #endif
160 
161 void nav_init(void)
162 {
163  waypoints_init();
164 
165  nav_block = 0;
166  nav_stage = 0;
167  nav_altitude = POS_BFP_OF_REAL(SECURITY_HEIGHT);
169  flight_altitude = SECURITY_ALT;
170  VECT3_COPY(navigation_target, waypoints[WP_HOME].enu_i);
171  VECT3_COPY(navigation_carrot, waypoints[WP_HOME].enu_i);
172 
175 
176  nav_roll = 0;
177  nav_pitch = 0;
178  nav_heading = 0;
179  nav_cmd_roll = 0;
180  nav_cmd_pitch = 0;
181  nav_cmd_yaw = 0;
185  nav_throttle = 0;
186  nav_climb = 0;
187  nav_leg_progress = 0;
188  nav_leg_length = 1;
189 
190  too_far_from_home = false;
191  dist2_to_home = 0;
192  dist2_to_wp = 0;
193 
194 #if PERIODIC_TELEMETRY
195  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_ROTORCRAFT_NAV_STATUS, send_nav_status);
197 #endif
198 }
199 
200 static inline void UNUSED nav_advance_carrot(void)
201 {
202  struct EnuCoor_i *pos = stateGetPositionEnu_i();
203  /* compute a vector to the waypoint */
204  struct Int32Vect2 path_to_waypoint;
205  VECT2_DIFF(path_to_waypoint, navigation_target, *pos);
206 
207  /* saturate it */
208  VECT2_STRIM(path_to_waypoint, -(1 << 15), (1 << 15));
209 
210  int32_t dist_to_waypoint = int32_vect2_norm(&path_to_waypoint);
211 
212  if (dist_to_waypoint < CLOSE_TO_WAYPOINT) {
214  } else {
215  struct Int32Vect2 path_to_carrot;
216  VECT2_SMUL(path_to_carrot, path_to_waypoint, CARROT_DIST);
217  VECT2_SDIV(path_to_carrot, path_to_carrot, dist_to_waypoint);
218  VECT2_SUM(navigation_carrot, path_to_carrot, *pos);
219  }
220 }
221 
222 void nav_run(void)
223 {
224 
225 #if GUIDANCE_H_USE_REF
226  // if GUIDANCE_H_USE_REF, CARROT_DIST is not used
228 #else
230 #endif
231 
233 }
234 
235 void nav_circle(struct EnuCoor_i *wp_center, int32_t radius)
236 {
237  if (radius == 0) {
238  VECT2_COPY(navigation_target, *wp_center);
239  dist2_to_wp = get_dist2_to_point(wp_center);
240  } else {
241  struct Int32Vect2 pos_diff;
242  VECT2_DIFF(pos_diff, *stateGetPositionEnu_i(), *wp_center);
243  // go back to half metric precision or values are too large
244  //INT32_VECT2_RSHIFT(pos_diff,pos_diff,INT32_POS_FRAC/2);
245  // store last qdr
246  int32_t last_qdr = nav_circle_qdr;
247  // compute qdr
248  nav_circle_qdr = int32_atan2(pos_diff.y, pos_diff.x);
249  // increment circle radians
250  if (nav_circle_radians != 0) {
251  int32_t angle_diff = nav_circle_qdr - last_qdr;
252  INT32_ANGLE_NORMALIZE(angle_diff);
253  nav_circle_radians += angle_diff;
254  } else {
255  // Smallest angle to increment at next step
256  nav_circle_radians = 1;
257  }
258 
259  // direction of rotation
260  int8_t sign_radius = radius > 0 ? 1 : -1;
261  // absolute radius
262  int32_t abs_radius = abs(radius);
263  // carrot_angle
264  int32_t carrot_angle = ((CARROT_DIST << INT32_ANGLE_FRAC) / abs_radius);
265  Bound(carrot_angle, (INT32_ANGLE_PI / 16), INT32_ANGLE_PI_4);
266  carrot_angle = nav_circle_qdr - sign_radius * carrot_angle;
267  int32_t s_carrot, c_carrot;
268  PPRZ_ITRIG_SIN(s_carrot, carrot_angle);
269  PPRZ_ITRIG_COS(c_carrot, carrot_angle);
270  // compute setpoint
271  VECT2_ASSIGN(pos_diff, abs_radius * c_carrot, abs_radius * s_carrot);
272  INT32_VECT2_RSHIFT(pos_diff, pos_diff, INT32_TRIG_FRAC);
273  VECT2_SUM(navigation_target, *wp_center, pos_diff);
274  }
275  nav_circle_center = *wp_center;
278 }
279 
280 
281 void nav_route(struct EnuCoor_i *wp_start, struct EnuCoor_i *wp_end)
282 {
283  struct Int32Vect2 wp_diff, pos_diff, wp_diff_prec;
284  VECT2_DIFF(wp_diff, *wp_end, *wp_start);
285  VECT2_DIFF(pos_diff, *stateGetPositionEnu_i(), *wp_start);
286  // go back to metric precision or values are too large
287  VECT2_COPY(wp_diff_prec, wp_diff);
288  INT32_VECT2_RSHIFT(wp_diff, wp_diff, INT32_POS_FRAC);
289  INT32_VECT2_RSHIFT(pos_diff, pos_diff, INT32_POS_FRAC);
290  uint32_t leg_length2 = Max((wp_diff.x * wp_diff.x + wp_diff.y * wp_diff.y), 1);
291  nav_leg_length = int32_sqrt(leg_length2);
292  nav_leg_progress = (pos_diff.x * wp_diff.x + pos_diff.y * wp_diff.y) / nav_leg_length;
293  int32_t progress = Max((CARROT_DIST >> INT32_POS_FRAC), 0);
294  nav_leg_progress += progress;
295  int32_t prog_2 = nav_leg_length;
296  Bound(nav_leg_progress, 0, prog_2);
297  struct Int32Vect2 progress_pos;
298  VECT2_SMUL(progress_pos, wp_diff_prec, ((float)nav_leg_progress) / nav_leg_length);
299  VECT2_SUM(navigation_target, *wp_start, progress_pos);
300 
301  nav_segment_start = *wp_start;
302  nav_segment_end = *wp_end;
304 
306 }
307 
308 bool nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_t approaching_time)
309 {
310  int32_t dist_to_point;
311  struct Int32Vect2 diff;
312  struct EnuCoor_i *pos = stateGetPositionEnu_i();
313 
314  /* if an approaching_time is given, estimate diff after approching_time secs */
315  if (approaching_time > 0) {
316  struct Int32Vect2 estimated_pos;
317  struct Int32Vect2 estimated_progress;
318  struct EnuCoor_i *speed = stateGetSpeedEnu_i();
319  VECT2_SMUL(estimated_progress, *speed, approaching_time);
320  INT32_VECT2_RSHIFT(estimated_progress, estimated_progress, (INT32_SPEED_FRAC - INT32_POS_FRAC));
321  VECT2_SUM(estimated_pos, *pos, estimated_progress);
322  VECT2_DIFF(diff, *wp, estimated_pos);
323  }
324  /* else use current position */
325  else {
326  VECT2_DIFF(diff, *wp, *pos);
327  }
328  /* compute distance of estimated/current pos to target wp
329  * distance with half metric precision (6.25 cm)
330  */
331  INT32_VECT2_RSHIFT(diff, diff, INT32_POS_FRAC / 2);
332  dist_to_point = int32_vect2_norm(&diff);
333 
334  /* return TRUE if we have arrived */
335  if (dist_to_point < BFP_OF_REAL(ARRIVED_AT_WAYPOINT, INT32_POS_FRAC / 2)) {
336  return true;
337  }
338 
339  /* if coming from a valid waypoint */
340  if (from != NULL) {
341  /* return TRUE if normal line at the end of the segment is crossed */
342  struct Int32Vect2 from_diff;
343  VECT2_DIFF(from_diff, *wp, *from);
344  INT32_VECT2_RSHIFT(from_diff, from_diff, INT32_POS_FRAC / 2);
345  return (diff.x * from_diff.x + diff.y * from_diff.y < 0);
346  }
347 
348  return false;
349 }
350 
351 bool nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time)
352 {
353  uint16_t time_at_wp;
354  uint32_t dist_to_point;
355  static uint16_t wp_entry_time = 0;
356  static bool wp_reached = false;
357  static struct EnuCoor_i wp_last = { 0, 0, 0 };
358  struct Int32Vect2 diff;
359 
360  if ((wp_last.x != wp->x) || (wp_last.y != wp->y)) {
361  wp_reached = false;
362  wp_last = *wp;
363  }
364  VECT2_DIFF(diff, *wp, *stateGetPositionEnu_i());
365  INT32_VECT2_RSHIFT(diff, diff, INT32_POS_FRAC / 2);
366  dist_to_point = int32_vect2_norm(&diff);
367  if (dist_to_point < BFP_OF_REAL(ARRIVED_AT_WAYPOINT, INT32_POS_FRAC / 2)) {
368  if (!wp_reached) {
369  wp_reached = true;
370  wp_entry_time = autopilot_flight_time;
371  time_at_wp = 0;
372  } else {
373  time_at_wp = autopilot_flight_time - wp_entry_time;
374  }
375  } else {
376  time_at_wp = 0;
377  wp_reached = false;
378  }
379  if (time_at_wp > stay_time) {
380  INT_VECT3_ZERO(wp_last);
381  return true;
382  }
383  return false;
384 }
385 
386 static inline void nav_set_altitude(void)
387 {
388  static int32_t last_nav_alt = 0;
389  if (abs(nav_altitude - last_nav_alt) > (POS_BFP_OF_REAL(0.2))) {
391  last_nav_alt = nav_altitude;
392  }
393 }
394 
395 
398 {
400  /* update local ENU coordinates of global waypoints */
402  return 0;
403 }
404 
405 unit_t nav_reset_alt(void)
406 {
409  return 0;
410 }
411 
412 void nav_init_stage(void)
413 {
415  stage_time = 0;
416  nav_circle_radians = 0;
417 }
418 
419 #include <stdio.h>
421 {
422  RunOnceEvery(NAV_FREQ, { stage_time++; block_time++; });
423 
424  nav_survey_active = false;
425 
426  dist2_to_wp = 0;
427 
428  /* from flight_plan.h */
429  auto_nav();
430 
431  /* run carrot loop */
432  nav_run();
433 }
434 
435 void navigation_update_wp_from_speed(uint8_t wp, struct Int16Vect3 speed_sp, int16_t heading_rate_sp)
436 {
437  // MY_ASSERT(wp < nb_waypoint); FIXME
438  int32_t s_heading, c_heading;
439  PPRZ_ITRIG_SIN(s_heading, nav_heading);
440  PPRZ_ITRIG_COS(c_heading, nav_heading);
441  // FIXME : scale POS to SPEED
442  struct Int32Vect3 delta_pos;
443  VECT3_SDIV(delta_pos, speed_sp, NAV_FREQ); /* fixme :make sure the division is really a >> */
444  INT32_VECT3_RSHIFT(delta_pos, delta_pos, (INT32_SPEED_FRAC - INT32_POS_FRAC));
445  waypoints[wp].enu_i.x += (s_heading * delta_pos.x + c_heading * delta_pos.y) >> INT32_TRIG_FRAC;
446  waypoints[wp].enu_i.y += (c_heading * delta_pos.x - s_heading * delta_pos.y) >> INT32_TRIG_FRAC;
447  waypoints[wp].enu_i.z += delta_pos.z;
448  int32_t delta_heading = heading_rate_sp / NAV_FREQ;
449  delta_heading = delta_heading >> (INT32_SPEED_FRAC - INT32_POS_FRAC);
450  nav_heading += delta_heading;
451 
452  INT32_COURSE_NORMALIZE(nav_heading);
453  RunOnceEvery(10, DOWNLINK_SEND_WP_MOVED_ENU(DefaultChannel, DefaultDevice, &wp,
454  &(waypoints[wp].enu_i.x),
455  &(waypoints[wp].enu_i.y),
456  &(waypoints[wp].enu_i.z)));
457 }
458 
460 {
461  if (!autopilot_ground_detected) { return false; }
463  return true;
464 }
465 
467 {
468  return autopilot_in_flight;
469 }
470 
472 void nav_home(void)
473 {
475  VECT3_COPY(navigation_target, waypoints[WP_HOME].enu_i);
476 
478  nav_altitude = waypoints[WP_HOME].enu_i.z;
480 
482 
483  /* run carrot loop */
484  nav_run();
485 }
486 
497 void nav_set_manual(int32_t roll, int32_t pitch, int32_t yaw)
498 {
500  nav_cmd_roll = roll;
501  nav_cmd_pitch = pitch;
502  nav_cmd_yaw = yaw;
503 }
504 
507 {
508  struct EnuCoor_f *pos = stateGetPositionEnu_f();
509  struct FloatVect2 pos_diff;
510  pos_diff.x = POS_FLOAT_OF_BFP(p->x) - pos->x;
511  pos_diff.y = POS_FLOAT_OF_BFP(p->y) - pos->y;
512  return pos_diff.x * pos_diff.x + pos_diff.y * pos_diff.y;
513 }
514 
517 {
518  return get_dist2_to_point(&waypoints[wp_id].enu_i);
519 }
520 
525 {
528 #ifdef InGeofenceSector
529  struct EnuCoor_f *pos = stateGetPositionEnu_f();
530  too_far_from_home = too_far_from_home || !(InGeofenceSector(pos->x, pos->y));
531 #endif
532 }
533 
535 bool nav_set_heading_rad(float rad)
536 {
539  return false;
540 }
541 
543 bool nav_set_heading_deg(float deg)
544 {
545  return nav_set_heading_rad(RadOfDeg(deg));
546 }
547 
549 bool nav_set_heading_towards(float x, float y)
550 {
551  struct FloatVect2 target = {x, y};
552  struct FloatVect2 pos_diff;
553  VECT2_DIFF(pos_diff, target, *stateGetPositionEnu_f());
554  // don't change heading if closer than 0.5m to target
555  if (VECT2_NORM2(pos_diff) > 0.25) {
556  float heading_f = atan2f(pos_diff.x, pos_diff.y);
557  nav_heading = ANGLE_BFP_OF_REAL(heading_f);
558  }
559  // return false so it can be called from the flightplan
560  // meaning it will continue to the next stage
561  return false;
562 }
563 
566 {
568 }
569 
572 {
574  return false;
575 }
576 
577 /************** Oval Navigation **********************************************/
578 
588 #ifndef LINE_START_FUNCTION
589 #define LINE_START_FUNCTION {}
590 #endif
591 #ifndef LINE_STOP_FUNCTION
592 #define LINE_STOP_FUNCTION {}
593 #endif
594 
597 
598 void nav_oval_init(void)
599 {
600  oval_status = OC2;
601  nav_oval_count = 0;
602 }
603 
604 void nav_oval(uint8_t p1, uint8_t p2, float radius)
605 {
606  radius = - radius; /* Historical error ? */
607  int32_t alt = waypoints[p1].enu_i.z;
608  waypoints[p2].enu_i.z = alt;
609 
610  float p2_p1_x = waypoints[p1].enu_f.x - waypoints[p2].enu_f.x;
611  float p2_p1_y = waypoints[p1].enu_f.y - waypoints[p2].enu_f.y;
612  float d = sqrtf(p2_p1_x * p2_p1_x + p2_p1_y * p2_p1_y);
613 
614  /* Unit vector from p1 to p2 */
615  int32_t u_x = POS_BFP_OF_REAL(p2_p1_x / d);
616  int32_t u_y = POS_BFP_OF_REAL(p2_p1_y / d);
617 
618  /* The half circle centers and the other leg */
619  struct EnuCoor_i p1_center = { waypoints[p1].enu_i.x + radius * -u_y,
620  waypoints[p1].enu_i.y + radius * u_x,
621  alt
622  };
623  struct EnuCoor_i p1_out = { waypoints[p1].enu_i.x + 2 * radius * -u_y,
624  waypoints[p1].enu_i.y + 2 * radius * u_x,
625  alt
626  };
627 
628  struct EnuCoor_i p2_in = { waypoints[p2].enu_i.x + 2 * radius * -u_y,
629  waypoints[p2].enu_i.y + 2 * radius * u_x,
630  alt
631  };
632  struct EnuCoor_i p2_center = { waypoints[p2].enu_i.x + radius * -u_y,
633  waypoints[p2].enu_i.y + radius * u_x,
634  alt
635  };
636 
637  int32_t qdr_out_2 = INT32_ANGLE_PI - int32_atan2_2(u_y, u_x);
638  int32_t qdr_out_1 = qdr_out_2 + INT32_ANGLE_PI;
639  if (radius < 0) {
640  qdr_out_2 += INT32_ANGLE_PI;
641  qdr_out_1 += INT32_ANGLE_PI;
642  }
643  int32_t qdr_anticipation = ANGLE_BFP_OF_REAL(radius > 0 ? -15 : 15);
644 
645  switch (oval_status) {
646  case OC1 :
647  nav_circle(&p1_center, POS_BFP_OF_REAL(-radius));
648  if (NavQdrCloseTo(INT32_DEG_OF_RAD(qdr_out_1) - qdr_anticipation)) {
649  oval_status = OR12;
650  InitStage();
652  }
653  return;
654 
655  case OR12:
656  nav_route(&p1_out, &p2_in);
657  if (nav_approaching_from(&p2_in, &p1_out, CARROT)) {
658  oval_status = OC2;
659  nav_oval_count++;
660  InitStage();
662  }
663  return;
664 
665  case OC2 :
666  nav_circle(&p2_center, POS_BFP_OF_REAL(-radius));
667  if (NavQdrCloseTo(INT32_DEG_OF_RAD(qdr_out_2) - qdr_anticipation)) {
668  oval_status = OR21;
669  InitStage();
671  }
672  return;
673 
674  case OR21:
675  nav_route(&waypoints[p2].enu_i, &waypoints[p1].enu_i);
676  if (nav_approaching_from(&waypoints[p1].enu_i, &waypoints[p2].enu_i, CARROT)) {
677  oval_status = OC1;
678  InitStage();
680  }
681  return;
682 
683  default: /* Should not occur !!! Doing nothing */
684  return;
685  }
686 }
687 /*
688 #ifdef TRAFFIC_INFO
689 #include "modules/multi/traffic_info.h"
690 
691 void nav_follow(uint8_t ac_id, uint32_t distance, uint32_t height)
692 {
693  struct EnuCoor_i* target = acInfoGetPositionEnu_i(ac_id);
694 
695 
696  float alpha = M_PI / 2 - acInfoGetCourse(ac_id);
697  float ca = cosf(alpha), sa = sinf(alpha);
698  target->x += - distance * ca;
699  target->y += - distance * sa;
700  target->z = (Max(target->z + height, SECURITY_HEIGHT)); // todo add ground height to check
701 
702  ENU_OF_TO_NED(navigation_target, *target);
703 }
704 #else*/
705 void nav_follow(uint8_t __attribute__((unused)) _ac_id, uint32_t __attribute__((unused)) distance,
706  uint32_t __attribute__((unused)) height) {}
707 //#endif
int32_t psi
in rad with INT32_ANGLE_FRAC
uint16_t block_time
unsigned short uint16_t
Definition: types.h:16
arch independent UART (Universal Asynchronous Receiver/Transmitter) API
float x
Definition: common_nav.h:40
int32_t y
North.
int32_t x
East.
#define INT32_SPEED_FRAC
#define INT32_DEG_OF_RAD(_rad)
Periodic telemetry system header (includes downlink utility and generated code).
uint16_t autopilot_flight_time
flight time in seconds.
Definition: autopilot.c:48
#define VECT2_SUM(_c, _a, _b)
Definition: pprz_algebra.h:85
#define INT32_ANGLE_FRAC
#define VECT2_STRIM(_v, _min, _max)
Definition: pprz_algebra.h:109
vector in East North Up coordinates Units: meters
#define POS_BFP_OF_REAL(_af)
#define VECT3_COPY(_a, _b)
Definition: pprz_algebra.h:139
static float radius
Definition: chemotaxis.c:15
#define VECT2_COPY(_a, _b)
Definition: pprz_algebra.h:67
#define InitStage()
#define VECT2_DIFF(_c, _a, _b)
Definition: pprz_algebra.h:91
uint8_t nav_block
Integrated Navigation System interface.
#define INT32_VECT3_RSHIFT(_o, _i, _r)
Autopilot modes.
#define VECT2_ASSIGN(_a, _x, _y)
Definition: pprz_algebra.h:61
static uint32_t int32_vect2_norm(struct Int32Vect2 *v)
return norm of 2D vector
static struct EnuCoor_f * stateGetPositionEnu_f(void)
Get position in local ENU coordinates (float).
Definition: state.h:713
void ins_reset_local_origin(void)
INS local origin reset.
Definition: ins_skeleton.c:136
#define BFP_OF_REAL(_vr, _frac)
#define PPRZ_ITRIG_SIN(_s, _a)
float y
Definition: common_nav.h:41
bool autopilot_ground_detected
Definition: autopilot.c:82
#define WaypointX(_wp)
Definition: common_nav.h:45
float x
in meters
Device independent GPS code (interface)
#define INT32_ANGLE_NORMALIZE(_a)
unsigned long uint32_t
Definition: types.h:18
signed short int16_t
Definition: types.h:17
#define VECT3_SDIV(_vo, _vi, _s)
Definition: pprz_algebra.h:195
uint32_t int32_sqrt(uint32_t in)
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
#define VECT2_NORM2(_v)
Definition: pprz_algebra.h:117
#define INT32_POS_FRAC
#define Max(x, y)
Definition: main_fbw.c:53
uint16_t stage_time
In s.
#define WaypointY(_wp)
Definition: common_nav.h:46
#define VECT2_SMUL(_vo, _vi, _s)
Definition: pprz_algebra.h:97
const uint8_t nb_waypoint
Definition: common_nav.c:37
signed long int32_t
Definition: types.h:19
#define ANGLE_BFP_OF_REAL(_af)
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:73
uint8_t nav_stage
#define INT32_TRIG_FRAC
#define VECT2_SDIV(_vo, _vi, _s)
Definition: pprz_algebra.h:103
#define INT_VECT3_ZERO(_v)
#define INT32_ANGLE_PI_4
vector in East North Up coordinates
unsigned char uint8_t
Definition: types.h:14
API to get/set the generic vehicle states.
int32_t int32_atan2_2(int32_t y, int32_t x)
static struct EnuCoor_i * stateGetSpeedEnu_i(void)
Get ground speed in local ENU coordinates (int).
Definition: state.h:860
struct point waypoints[NB_WAYPOINT]
size == nb_waypoint, waypoint 0 is a dummy waypoint
Definition: common_nav.c:38
#define INT32_COURSE_NORMALIZE(_a)
Horizontal guidance for rotorcrafts.
#define INT32_ANGLE_PI
static float p[2][2]
#define POS_FLOAT_OF_BFP(_ai)
bool autopilot_in_flight
Definition: autopilot.c:72
static struct EnuCoor_i * stateGetPositionEnu_i(void)
Get position in local ENU coordinates (int).
Definition: state.h:668
#define INT32_VECT2_RSHIFT(_o, _i, _r)
signed char int8_t
Definition: types.h:15
void waypoints_localize_all(void)
update local ENU coordinates of global waypoints
Definition: waypoints.c:265
static struct Int32Eulers * stateGetNedToBodyEulers_i(void)
Get vehicle body attitude euler angles (int).
Definition: state.h:1107
float y
in meters
void ins_reset_altitude_ref(void)
INS altitude reference reset.
void waypoints_init(void)
initialize global and local waypoints
Definition: waypoints.c:35
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:46
#define PPRZ_ITRIG_COS(_c, _a)
int32_t int32_atan2(int32_t y, int32_t x)
Paparazzi fixed point algebra.