Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
navigation.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008-2009 Antoine Drouin <poinix@gmail.com>
3  * Copyright (C) 2022 Gautier Hattenberger <gautier.hattenberger@enac.fr>
4  *
5  * This file is part of paparazzi.
6  *
7  * paparazzi is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2, or (at your option)
10  * any later version.
11  *
12  * paparazzi is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with paparazzi; see the file COPYING. If not, see
19  * <http://www.gnu.org/licenses/>.
20  */
21 
29 #define NAV_C
30 
32 
33 #include "pprz_debug.h"
34 #include "state.h"
35 #include "autopilot.h"
36 #include "generated/modules.h"
37 #include "generated/flight_plan.h"
38 #include "modules/ins/ins.h"
39 
40 /* for default GUIDANCE_H_USE_REF */
42 
43 #include "math/pprz_algebra_int.h"
44 
46 #include "pprzlink/messages.h"
47 #include "mcu_periph/uart.h"
48 
49 PRINT_CONFIG_VAR(NAVIGATION_FREQUENCY)
50 
52 
53 const float max_dist_from_home = MAX_DIST_FROM_HOME;
54 const float max_dist2_from_home = MAX_DIST_FROM_HOME * MAX_DIST_FROM_HOME;
55 
57 
60 static void empty_stage_init(void) {}
61 static void empty_goto(struct EnuCoor_f *wp UNUSED) {}
62 static void empty_route(struct EnuCoor_f *wp_start UNUSED, struct EnuCoor_f *wp_end UNUSED) {}
63 static bool empty_approaching(struct EnuCoor_f *wp_to UNUSED, struct EnuCoor_f *wp_from UNUSED, float approaching_time UNUSED) { return true; }
64 static void empty_circle(struct EnuCoor_f *wp_center UNUSED, float radius UNUSED) {}
65 static void empty_oval_init(void) {}
66 static void empty_oval(struct EnuCoor_f *wp1 UNUSED, struct EnuCoor_f *wp2 UNUSED, float radius UNUSED) {};
67 
68 static inline void nav_set_altitude(void);
69 
70 void nav_init(void)
71 {
73 
74  nav_block = 0;
75  nav_stage = 0;
76 
80 
81  VECT3_COPY(nav.target, waypoints[WP_HOME].enu_f);
82  VECT3_COPY(nav.carrot, waypoints[WP_HOME].enu_f);
87 
88  nav.throttle = 0;
89  nav.roll = 0.f;
90  nav.pitch = 0.f;
91  nav.heading = 0.f;
93  nav.climb = 0.f;
94  nav.fp_altitude = SECURITY_HEIGHT;
95  nav.nav_altitude = SECURITY_HEIGHT;
96  flight_altitude = SECURITY_ALT;
97 
98  nav.too_far_from_home = false;
100  nav.dist2_to_home = 0.f;
103 
111 
112  // generated init function
113  auto_nav_init();
114 }
115 
117 {
118  if (DL_BLOCK_ac_id(buf) != AC_ID) { return; }
119  nav_goto_block(DL_BLOCK_block_id(buf));
120 }
121 
123 {
124  uint8_t ac_id = DL_MOVE_WP_ac_id(buf);
125  if (ac_id != AC_ID) { return; }
127  uint8_t wp_id = DL_MOVE_WP_wp_id(buf);
128  struct LlaCoor_i lla;
129  lla.lat = DL_MOVE_WP_lat(buf);
130  lla.lon = DL_MOVE_WP_lon(buf);
131  /* WP_alt from message is alt above MSL in mm
132  * lla.alt is above ellipsoid in mm
133  */
134  lla.alt = DL_MOVE_WP_alt(buf) - state.ned_origin_i.hmsl +
136  waypoint_move_lla(wp_id, &lla);
137  }
138 }
139 
140 #ifndef CLOSE_TO_WAYPOINT
141 #define CLOSE_TO_WAYPOINT 15.f
142 #endif
143 
144 static inline void UNUSED nav_advance_carrot(void)
145 {
146  struct EnuCoor_f *pos = stateGetPositionEnu_f();
147  /* compute a vector to the waypoint */
148  struct FloatVect2 path_to_waypoint;
149  VECT2_DIFF(path_to_waypoint, nav.target, *pos);
150 
151  /* saturate it */
152  VECT2_STRIM(path_to_waypoint, -150.f, 150.f);
153 
154  float dist_to_waypoint = float_vect2_norm(&path_to_waypoint);
155 
156  if (dist_to_waypoint < CLOSE_TO_WAYPOINT) {
158  } else {
159  struct Int32Vect2 path_to_carrot;
160  VECT2_SMUL(path_to_carrot, path_to_waypoint, NAV_CARROT_DIST);
161  VECT2_SDIV(path_to_carrot, path_to_carrot, dist_to_waypoint);
162  VECT2_SUM(nav.carrot, path_to_carrot, *pos);
163  }
164 }
165 
166 void nav_run(void)
167 {
168 
169 #if GUIDANCE_H_USE_REF
170  // if GUIDANCE_H_USE_REF, CARROT_DIST is not used
172 #else
174 #endif
175 
176  // update altitude setpoint if needed
178 }
179 
180 
181 bool nav_check_wp_time(struct EnuCoor_f *wp, uint16_t stay_time)
182 {
183  uint16_t time_at_wp;
184  float dist_to_point;
185  static uint16_t wp_entry_time = 0;
186  static bool wp_reached = false;
187  static struct EnuCoor_i wp_last = { 0, 0, 0 };
188  struct EnuCoor_i wp_i;
189  struct FloatVect2 diff;
190 
191  ENU_BFP_OF_REAL(wp_i, *wp);
192  if ((wp_last.x != wp_i.x) || (wp_last.y != wp_i.y)) {
193  wp_reached = false;
194  wp_last = wp_i;
195  }
196 
197  VECT2_DIFF(diff, *wp, *stateGetPositionEnu_f());
198  dist_to_point = float_vect2_norm(&diff);
199  if (dist_to_point < ARRIVED_AT_WAYPOINT) {
200  if (!wp_reached) {
201  wp_reached = true;
202  wp_entry_time = autopilot.flight_time;
203  time_at_wp = 0;
204  } else {
205  time_at_wp = autopilot.flight_time - wp_entry_time;
206  }
207  } else {
208  time_at_wp = 0;
209  wp_reached = false;
210  }
211  if (time_at_wp > stay_time) {
212  INT_VECT3_ZERO(wp_last);
213  return true;
214  }
215  return false;
216 }
217 
218 static inline void nav_set_altitude(void)
219 {
220  static float last_alt = 0.f;
221  // if the fp_altitude setpoint change is large enough, set this alt as the new reference
222  // otherwise, don't change nav_altitude (whose value can be changed by the operator
223  // through the flight_altitude setting)
224  // nav_altitude is the value that is used by guidance as a setpoint when flying in
225  // altitude mode
226  if (fabsf(nav.fp_altitude - last_alt) > 0.2f) {
229  last_alt = nav.fp_altitude;
230  }
231 }
232 
233 
236 {
238  /* update local ENU coordinates of global waypoints */
240 }
241 
242 void nav_reset_alt(void)
243 {
246 }
247 
248 void nav_init_stage(void)
249 {
250  stage_time = 0;
251  if (nav.nav_stage_init) {
253  }
254 }
255 
256 #include <stdio.h>
258 {
259  RunOnceEvery(NAVIGATION_FREQUENCY, { stage_time++; block_time++; });
260 
261  /* from flight_plan.h */
262  auto_nav();
263 
264  /* run carrot loop */
265  nav_run();
266 }
267 
269 {
270  if (!autopilot.ground_detected) { return false; }
271  autopilot.ground_detected = false;
272  return true;
273 }
274 
276 {
277  return autopilot_in_flight();
278 }
279 
280 void nav_glide_points(struct EnuCoor_f *start_point, struct EnuCoor_f *end_point)
281 {
282  struct FloatVect2 wp_diff, pos_diff;
283  VECT2_DIFF(wp_diff, *end_point, *start_point);
284  VECT2_DIFF(pos_diff, *stateGetPositionEnu_f(), *start_point);
285  float length2 = Max(float_vect2_norm2(&wp_diff), 0.1f);
286  float progress = (pos_diff.x * wp_diff.x + pos_diff.y * wp_diff.y) / length2;
287  float alt = start_point->z + (end_point->z - start_point->z) * progress;
288  NavVerticalAltitudeMode(alt, 0);
289 }
290 
292 void nav_home(void)
293 {
296  VECT3_COPY(nav.target, waypoints[WP_HOME].enu_f);
297 
299  nav.nav_altitude = waypoint_get_alt(WP_HOME);
300 
301  /* run carrot loop */
302  nav_run();
303 }
304 
307 {
308  struct EnuCoor_f *pos = stateGetPositionEnu_f();
309  struct FloatVect2 pos_diff;
310  pos_diff.x = p->x - pos->x;
311  pos_diff.y = p->y - pos->y;
312  return pos_diff.x * pos_diff.x + pos_diff.y * pos_diff.y;
313 }
314 
317 {
318  return get_dist2_to_point(&waypoints[wp_id].enu_f);
319 }
320 
325 {
328 #ifdef InGeofenceSector
329  struct EnuCoor_f *pos = stateGetPositionEnu_f();
330  nav.too_far_from_home = nav.too_far_from_home || !(InGeofenceSector(pos->x, pos->y));
331 #endif
332 }
333 
335 void nav_set_heading_rad(float rad)
336 {
337  nav.heading = rad;
339 }
340 
342 void nav_set_heading_deg(float deg)
343 {
344  nav_set_heading_rad(RadOfDeg(deg));
345 }
346 
348 void nav_set_heading_towards(float x, float y)
349 {
350  struct FloatVect2 target = {x, y};
351  struct FloatVect2 pos_diff;
353  // don't change heading if closer than 0.5m to target
354  if (VECT2_NORM2(pos_diff) > 0.25f) {
355  float heading_f = atan2f(pos_diff.x, pos_diff.y);
356  nav.heading = heading_f;
357  }
358 }
359 
362 {
364 }
365 
368 {
370 }
371 
374 {
376 }
377 
379 {
381 }
382 
386 {
388 }
389 
391 {
395 }
396 
398 {
400 }
401 
403 {
406 }
407 
bool autopilot_set_mode(uint8_t new_autopilot_mode)
set autopilot mode
Definition: autopilot.c:193
struct pprz_autopilot autopilot
Global autopilot structure.
Definition: autopilot.c:49
bool autopilot_in_flight(void)
get in_flight flag
Definition: autopilot.c:335
Core autopilot interface common to all firmwares.
bool ground_detected
automatic detection of landing
Definition: autopilot.h:73
uint16_t flight_time
flight time in seconds
Definition: autopilot.h:65
uint8_t nav_stage
uint8_t last_wp UNUSED
uint8_t nav_block
uint16_t stage_time
In s.
void nav_goto_block(uint8_t b)
uint16_t block_time
struct point waypoints[NB_WAYPOINT]
size == nb_waypoint, waypoint 0 is a dummy waypoint
Definition: common_nav.c:39
#define WaypointX(_wp)
Definition: common_nav.h:45
#define WaypointY(_wp)
Definition: common_nav.h:46
float psi
in radians
static void float_quat_identity(struct FloatQuat *q)
initialises a quaternion to identity
static float float_vect2_norm2(struct FloatVect2 *v)
#define FLOAT_VECT3_ZERO(_v)
static float float_vect2_norm(struct FloatVect2 *v)
#define FLOAT_RATES_ZERO(_r)
#define VECT2_SMUL(_vo, _vi, _s)
Definition: pprz_algebra.h:98
#define VECT2_DIFF(_c, _a, _b)
Definition: pprz_algebra.h:92
#define VECT2_STRIM(_v, _min, _max)
Definition: pprz_algebra.h:110
#define VECT2_COPY(_a, _b)
Definition: pprz_algebra.h:68
#define VECT2_SUM(_c, _a, _b)
Definition: pprz_algebra.h:86
#define VECT2_SDIV(_vo, _vi, _s)
Definition: pprz_algebra.h:104
#define VECT3_COPY(_a, _b)
Definition: pprz_algebra.h:140
#define VECT2_NORM2(_v)
Definition: pprz_algebra.h:118
#define INT_VECT3_ZERO(_v)
int32_t lat
in degrees*1e7
int32_t y
North.
int32_t hmsl
Height above mean sea level in mm.
int32_t alt
in millimeters above WGS84 reference ellipsoid
struct LlaCoor_i lla
Reference point in lla.
int32_t x
East.
int32_t lon
in degrees*1e7
#define ENU_BFP_OF_REAL(_o, _i)
vector in East North Up coordinates
vector in Latitude, Longitude and Altitude
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition: state.h:1143
struct State state
Definition: state.c:36
static struct EnuCoor_f * stateGetPositionEnu_f(void)
Get position in local ENU coordinates (float).
Definition: state.h:719
struct LtpDef_f ned_origin_f
Definition of the local (flat earth) coordinate system.
Definition: state.h:220
struct LtpDef_i ned_origin_i
Definition of the local (flat earth) coordinate system.
Definition: state.h:166
static bool stateIsLocalCoordinateValid(void)
Test if local coordinates are valid.
Definition: state.h:508
void WEAK ins_reset_local_origin(void)
INS local origin reset.
Definition: ins.c:55
void WEAK ins_reset_altitude_ref(void)
INS altitude reference reset.
Definition: ins.c:65
Integrated Navigation System interface.
static float p[2][2]
void waypoints_localize_all(void)
update local ENU coordinates of global waypoints
Definition: waypoints.c:357
float waypoint_get_alt(uint8_t wp_id)
Get altitude of waypoint in meters (above reference)
Definition: waypoints.c:113
void waypoints_init(void)
initialize global and local waypoints
Definition: waypoints.c:51
void waypoint_move_lla(uint8_t wp_id, struct LlaCoor_i *lla)
Definition: waypoints.c:253
void nav_oval(uint8_t p1, uint8_t p2, float radius)
Definition: nav.c:763
#define NAVIGATION_FREQUENCY
Default fixedwing navigation frequency.
Definition: nav.h:49
#define NavVerticalAltitudeMode(_alt, _pre_climb)
Set the vertical mode to altitude control with the specified altitude setpoint and climb pre-command.
Definition: nav.h:191
static void nav_goto(struct EnuCoor_f *wp)
static void _nav_oval_init(void)
static void nav_route(struct EnuCoor_f *wp_start, struct EnuCoor_f *wp_end)
static void nav_circle(struct EnuCoor_f *wp_center, float radius)
static bool nav_approaching(struct EnuCoor_f *wp, struct EnuCoor_f *from, float approaching_time)
static void nav_stage_init(void)
Implement basic nav function.
struct FloatVect2 pos_diff
Paparazzi fixed point algebra.
float y
in meters
float x
in meters
float hmsl
Height above mean sea level in meters.
float z
in meters
vector in East North Up coordinates Units: meters
#define AP_MODE_FAILSAFE
Horizontal guidance for rotorcrafts.
void nav_home(void)
Home mode navigation.
Definition: navigation.c:292
static void empty_oval_init(void)
Definition: navigation.c:65
static bool empty_approaching(struct EnuCoor_f *wp_to UNUSED, struct EnuCoor_f *wp_from UNUSED, float approaching_time UNUSED)
Definition: navigation.c:63
float flight_altitude
Dynamically adjustable, reset to nav_altitude when it is changing.
Definition: navigation.c:56
void nav_reset_reference(void)
Reset the geographic reference to the current GPS fix.
Definition: navigation.c:235
void nav_register_oval(navigation_oval_init _nav_oval_init, navigation_oval nav_oval)
Definition: navigation.c:402
void nav_set_heading_current(void)
Set heading to the current yaw angle.
Definition: navigation.c:373
void nav_init_stage(void)
needs to be implemented by fixedwing and rotorcraft seperately
Definition: navigation.c:248
void nav_reset_alt(void)
Definition: navigation.c:242
const float max_dist_from_home
Definition: navigation.c:53
void nav_set_heading_towards_waypoint(uint8_t wp)
Set heading in the direction of a waypoint.
Definition: navigation.c:361
void compute_dist2_to_home(void)
Computes squared distance to the HOME waypoint potentially sets too_far_from_home.
Definition: navigation.c:324
bool nav_is_in_flight(void)
Definition: navigation.c:275
void nav_run(void)
Definition: navigation.c:166
void nav_set_heading_towards(float x, float y)
Set heading to point towards x,y position in local coordinates.
Definition: navigation.c:348
struct RotorcraftNavigation nav
Definition: navigation.c:51
void nav_init(void)
Navigation Initialisation.
Definition: navigation.c:70
void nav_parse_MOVE_WP(uint8_t *buf)
Definition: navigation.c:122
void nav_register_circle(navigation_circle nav_circle)
Definition: navigation.c:397
void nav_register_goto_wp(navigation_goto nav_goto, navigation_route nav_route, navigation_approaching nav_approaching)
Registering functions.
Definition: navigation.c:390
static void empty_stage_init(void)
Empty navigation functions set at init.
Definition: navigation.c:60
static void empty_oval(struct EnuCoor_f *wp1 UNUSED, struct EnuCoor_f *wp2 UNUSED, float radius UNUSED)
Definition: navigation.c:66
void nav_parse_BLOCK(uint8_t *buf)
Definition: navigation.c:116
#define CLOSE_TO_WAYPOINT
Definition: navigation.c:141
static void empty_goto(struct EnuCoor_f *wp UNUSED)
Definition: navigation.c:61
void nav_set_heading_towards_target(void)
Set heading in the direction of the target.
Definition: navigation.c:367
float get_dist2_to_point(struct EnuCoor_f *p)
Returns squared horizontal distance to given point.
Definition: navigation.c:306
void nav_register_stage_init(navigation_stage_init nav_stage_init)
Register functions.
Definition: navigation.c:385
static void empty_route(struct EnuCoor_f *wp_start UNUSED, struct EnuCoor_f *wp_end UNUSED)
Definition: navigation.c:62
const float max_dist2_from_home
Definition: navigation.c:54
void nav_glide_points(struct EnuCoor_f *start_point, struct EnuCoor_f *end_point)
Definition: navigation.c:280
void nav_set_heading_rad(float rad)
Set nav_heading in radians.
Definition: navigation.c:335
bool nav_detect_ground(void)
Definition: navigation.c:268
void nav_set_heading_deg(float deg)
Set nav_heading in degrees.
Definition: navigation.c:342
static void empty_circle(struct EnuCoor_f *wp_center UNUSED, float radius UNUSED)
Definition: navigation.c:64
bool nav_check_wp_time(struct EnuCoor_f *wp, uint16_t stay_time)
Check the time spent in a radius of 'ARRIVED_AT_WAYPOINT' around a wp
Definition: navigation.c:181
void nav_periodic_task(void)
Navigation main: call to the code generated from the XML flight plan.
Definition: navigation.c:257
float get_dist2_to_waypoint(uint8_t wp_id)
Returns squared horizontal distance to given waypoint.
Definition: navigation.c:316
static void UNUSED nav_advance_carrot(void)
Definition: navigation.c:144
static void nav_set_altitude(void)
Definition: navigation.c:218
void nav_set_failsafe(void)
Definition: navigation.c:378
Rotorcraft navigation functions.
struct EnuCoor_f speed
speed setpoint (in m/s)
Definition: navigation.h:128
struct FloatRates rates
rates setpoint (in rad/s)
Definition: navigation.h:135
#define NAV_HORIZONTAL_MODE_WAYPOINT
Nav modes these modes correspond to the flight plan instructions used to set the high level navigatio...
Definition: navigation.h:85
uint32_t throttle
throttle command (in pprz_t)
Definition: navigation.h:130
float climb
climb setpoint (in m/s)
Definition: navigation.h:137
float dist2_to_home
squared distance to home waypoint
Definition: navigation.h:142
void(* navigation_goto)(struct EnuCoor_f *wp)
Definition: navigation.h:109
#define NAV_DESCEND_VSPEED
Definition: navigation.h:50
bool(* navigation_approaching)(struct EnuCoor_f *wp_to, struct EnuCoor_f *wp_from, float approaching_time)
Definition: navigation.h:111
float failsafe_mode_dist2
maximum squared distance to home wp before going to failsafe mode
Definition: navigation.h:144
void(* navigation_oval)(struct EnuCoor_f *wp1, struct EnuCoor_f *wp2, float radius)
Definition: navigation.h:114
navigation_stage_init nav_stage_init
Definition: navigation.h:149
navigation_oval nav_oval
Definition: navigation.h:155
navigation_approaching nav_approaching
Definition: navigation.h:152
struct FloatQuat quat
quaternion setpoint
Definition: navigation.h:134
#define DEFAULT_CIRCLE_RADIUS
default nav_circle_radius in meters
Definition: navigation.h:42
navigation_circle nav_circle
Definition: navigation.h:153
#define NAV_CARROT_DIST
Carrot distance during navigation.
Definition: navigation.h:65
void(* navigation_oval_init)(void)
Definition: navigation.h:113
struct EnuCoor_f accel
accel setpoint (in m/s)
Definition: navigation.h:129
float nav_altitude
current altitude setpoint (in meters): might differ from fp_altitude depending on altitude shift from...
Definition: navigation.h:139
#define NAV_VERTICAL_MODE_ALT
Definition: navigation.h:94
float radius
radius setpoint (in meters)
Definition: navigation.h:136
float descend_vspeed
descend speed setting, mostly used in flight plans
Definition: navigation.h:146
navigation_oval_init nav_oval_init
Definition: navigation.h:154
void(* navigation_route)(struct EnuCoor_f *wp_start, struct EnuCoor_f *wp_end)
Definition: navigation.h:110
float pitch
pitch angle (in radians)
Definition: navigation.h:132
void(* navigation_circle)(struct EnuCoor_f *wp_center, float radius)
Definition: navigation.h:112
float heading
heading setpoint (in radians)
Definition: navigation.h:133
struct EnuCoor_f carrot
carrot position (also used for GCS display)
Definition: navigation.h:127
navigation_goto nav_goto
Definition: navigation.h:150
navigation_route nav_route
Definition: navigation.h:151
#define NAV_SETPOINT_MODE_POS
Nav setpoint modes these modes correspond to submodes defined by navigation routines to tell which se...
Definition: navigation.h:100
float fp_altitude
altitude setpoint from flight plan (in meters)
Definition: navigation.h:138
void(* navigation_stage_init)(void)
Definition: navigation.h:108
#define FAILSAFE_MODE_DISTANCE
Maximum distance from HOME waypoint before going into failsafe mode.
Definition: navigation.h:60
struct EnuCoor_f target
final target position (in meters)
Definition: navigation.h:126
#define NAV_CLIMB_VSPEED
Definition: navigation.h:46
bool too_far_from_home
too_far flag
Definition: navigation.h:143
#define ARRIVED_AT_WAYPOINT
minimum horizontal distance to waypoint to mark as arrived
Definition: navigation.h:55
float climb_vspeed
climb speed setting, mostly used in flight plans
Definition: navigation.h:145
float roll
roll angle (in radians)
Definition: navigation.h:131
General Navigation structure.
Definition: navigation.h:119
#define NormCourseRad(x)
Normalize a rad angle between 0 and 2*PI.
Definition: navigation.h:156
API to get/set the generic vehicle states.
struct target_t target
Definition: target_pos.c:64
arch independent UART (Universal Asynchronous Receiver/Transmitter) API
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
Definition: vl53l1_types.h:88
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
Definition: vl53l1_types.h:98