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
nav.h File Reference

Fixedwing Navigation library. More...

+ Include dependency graph for nav.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Macros

#define NAV_GRAVITY   9.806
 
#define Square(_x)   ((_x)*(_x))
 
#define DistanceSquare(p1_x, p1_y, p2_x, p2_y)   (Square(p1_x-p2_x)+Square(p1_y-p2_y))
 
#define PowerVoltage()   (vsupply/10.)
 
#define RcRoll(travel)   (imcu_get_radio(RADIO_ROLL) * (float)travel /(float)MAX_PPRZ)
 
#define NAV_MODE_ROLL   1
 
#define NAV_MODE_COURSE   2
 
#define HORIZONTAL_MODE_WAYPOINT   0
 
#define HORIZONTAL_MODE_ROUTE   1
 
#define HORIZONTAL_MODE_CIRCLE   2
 
#define NavGotoWaypoint(_wp)
 
#define Eight(a, b, c)   nav_eight((a), (b), (c))
 
#define Oval(a, b, c)   nav_oval((b), (a), (c))
 
#define RCLost()   bit_is_set(imcu_get_status(), STATUS_RADIO_REALLY_LOST)
 
#define NavFollow(_ac_id, _distance, _height)   nav_follow(_ac_id, _distance, _height)
 
#define NavGlide(_start_wp, _wp)   nav_glide(_start_wp, _wp)
 
#define NavCircleWaypoint(wp, radius)   nav_circle_XY(waypoints[wp].x, waypoints[wp].y, radius)
 
#define NormCourse(x)
 Normalize a degree angle between 0 and 359. More...
 
#define NavCircleCountNoRewind()   (nav_circle_radians_no_rewind / (2*M_PI))
 
#define NavCircleCount()   (fabs(nav_circle_radians) / (2*M_PI))
 
#define NavCircleQdr()   ({ float qdr = DegOfRad(M_PI_2 - nav_circle_trigo_qdr); NormCourse(qdr); qdr; })
 
#define CloseDegAngles(_c1, _c2)   ({ float _diff = _c1 - _c2; NormCourse(_diff); 350 < _diff || _diff < 10; })
 
#define NavQdrCloseTo(x)   CloseDegAngles(x, NavCircleQdr())
 True if x (in degrees) is close to the current QDR (less than 10 degrees) More...
 
#define NavCourseCloseTo(x)   CloseDegAngles(x, DegOfRad(stateGetHorizontalSpeedDir_f()))
 
#define NavSegment(_start, _end)   nav_route_xy(waypoints[_start].x, waypoints[_start].y, waypoints[_end].x, waypoints[_end].y)
 
#define NavApproaching(wp, time)   nav_approaching_xy(waypoints[wp].x, waypoints[wp].y, last_x, last_y, time)
 
#define NavApproachingFrom(wp, from, time)   nav_approaching_xy(waypoints[wp].x, waypoints[wp].y, waypoints[from].x, waypoints[from].y, time)
 
#define NavVerticalAutoThrottleMode(_pitch)
 Set the climb control to auto-throttle with the specified pitch pre-command. More...
 
#define NavVerticalAutoPitchMode(_throttle)
 Set the climb control to auto-pitch with the specified throttle pre-command. More...
 
#define NavVerticalAltitudeMode(_alt, _pre_climb)
 Set the vertical mode to altitude control with the specified altitude setpoint and climb pre-command. More...
 
#define NavVerticalClimbMode(_climb)
 Set the vertical mode to climb control with the specified climb setpoint. More...
 
#define NavVerticalThrottleMode(_throttle)
 Set the vertical mode to fixed throttle with the specified setpoint. More...
 
#define NavHeading(_course)
 
#define NavAttitude(_roll)
 
#define NavSetManual(_roll, _pitch, _yaw)   _Pragma("GCC error \"Manual mode in flight plan for fixedwing is not available\"")
 
#define nav_IncreaseShift(x)   { if (x==0) nav_shift = 0; else nav_shift += x; }
 
#define nav_SetNavRadius(x)   { if (x==1) nav_radius = DEFAULT_CIRCLE_RADIUS; else if (x==-1) nav_radius = -DEFAULT_CIRCLE_RADIUS; else nav_radius = x; }
 
#define NavKillThrottle()   { kill_throttle = 1; }
 
#define GetPosX()   (stateGetPositionEnu_f()->x)
 Get current x (east) position in local coordinates. More...
 
#define GetPosY()   (stateGetPositionEnu_f()->y)
 Get current y (north) position in local coordinates. More...
 
#define GetPosAlt()   (stateGetPositionUtm_f()->alt)
 Get current altitude above MSL. More...
 
#define GetAltRef()   (ground_alt)
 Get current altitude reference for local coordinates. More...
 
#define SEND_NAVIGATION(_trans, _dev)
 
#define DownlinkSendWp(_trans, _dev, i)
 

Enumerations

enum  oval_status {
  OR12, OC2, OR21, OC1,
  OR12, OC2, OR21, OC1
}
 

Functions

void fly_to_xy (float x, float y)
 Computes desired_x, desired_y and desired_course. More...
 
void nav_eight_init (void)
 
void nav_eight (uint8_t, uint8_t, float)
 Navigation along a figure 8. More...
 
void nav_oval_init (void)
 
void nav_oval (uint8_t, uint8_t, float)
 
void nav_periodic_task (void)
 Navigation main: call to the code generated from the XML flight plan. More...
 
void nav_home (void)
 Home mode navigation (circle around HOME) More...
 
void nav_init (void)
 Navigation Initialisation. More...
 
void nav_without_gps (void)
 Failsafe navigation without position estimation. More...
 
void nav_circle_XY (float x, float y, float radius)
 Angle from center to mobile. More...
 
bool nav_compute_baseleg (uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, float radius)
 
bool nav_compute_final_from_glide (uint8_t wp_af, uint8_t wp_td, float glide)
 
void nav_follow (uint8_t _ac_id, float _distance, float _height)
 
void nav_glide (uint8_t start_wp, uint8_t wp)
 
void nav_route_xy (float last_wp_x, float last_wp_y, float wp_x, float wp_y)
 Computes the carrot position along the desired segment. More...
 
bool nav_approaching_xy (float x, float y, float from_x, float from_y, float approaching_time)
 Decide if the UAV is approaching the current waypoint. More...
 
bool DownlinkSendWpNr (uint8_t _wp)
 

Variables

float cur_pos_x
 
float cur_pos_y
 
float last_x
 
float last_y
 
float desired_x
 
float desired_y
 
float nav_altitude
 
float flight_altitude
 Dynamically adjustable, reset to nav_altitude when it is changing. More...
 
float nav_glide_pitch_trim
 
pprz_t nav_throttle_setpoint
 
float nav_pitch
 
float rc_pitch
 
float fp_pitch
 
float fp_throttle
 
float fp_climb
 
float carrot_x
 
float carrot_y
 
float nav_circle_radians
 Status on the current circle. More...
 
float nav_circle_radians_no_rewind
 
bool nav_in_circle
 
bool nav_in_segment
 
float nav_circle_x
 
float nav_circle_y
 
float nav_circle_radius
 
float nav_segment_x_1
 
float nav_segment_y_1
 
float nav_segment_x_2
 
float nav_segment_y_2
 
uint8_t last_wp
 Index of last waypoint. More...
 
int nav_mode
 
uint8_t horizontal_mode
 
uint8_t nav_oval_count
 Navigation along a figure O. More...
 
float nav_radius
 
float nav_course
 
float nav_climb
 
float nav_shift
 
float nav_ground_speed_pgain
 
float nav_ground_speed_setpoint
 
float nav_survey_shift
 
float nav_survey_west
 
float nav_survey_east
 
float nav_survey_north
 
float nav_survey_south
 
bool nav_survey_active
 
float nav_circle_trigo_qdr
 
float baseleg_out_qdr
 

Detailed Description

Fixedwing Navigation library.

This collection of macros and functions is used by the C code generated from the XML flight plan.

Definition in file nav.h.

Macro Definition Documentation

#define CloseDegAngles (   _c1,
  _c2 
)    ({ float _diff = _c1 - _c2; NormCourse(_diff); 350 < _diff || _diff < 10; })

Definition at line 151 of file nav.h.

#define DistanceSquare (   p1_x,
  p1_y,
  p2_x,
  p2_y 
)    (Square(p1_x-p2_x)+Square(p1_y-p2_y))

Definition at line 46 of file nav.h.

Referenced by nav_circle_XY().

#define DownlinkSendWp (   _trans,
  _dev,
 
)
Value:
{ \
float x = nav_utm_east0 + waypoints[i].x; \
float y = nav_utm_north0 + waypoints[i].y; \
pprz_msg_send_WP_MOVED(_trans, _dev, AC_ID, &i, &x, &y, &(waypoints[i].a),&nav_utm_zone0); \
}
float x
Definition: common_nav.h:40
uint8_t nav_utm_zone0
Definition: common_nav.c:44
float y
Definition: common_nav.h:41
int32_t nav_utm_north0
Definition: common_nav.c:43
int32_t nav_utm_east0
Definition: common_nav.c:42
struct point waypoints[NB_WAYPOINT]
size == nb_waypoint, waypoint 0 is a dummy waypoint
Definition: common_nav.c:38

Definition at line 247 of file nav.h.

Referenced by DownlinkSendWpNr(), nav_catapult_run(), and send_wp_moved().

#define Eight (   a,
  b,
 
)    nav_eight((a), (b), (c))

Definition at line 98 of file nav.h.

#define GetAltRef ( )    (ground_alt)

Get current altitude reference for local coordinates.

This is the ground_alt from the flight plan at first, but might be updated later through a call to NavSetGroundReferenceHere() or NavSetAltitudeReferenceHere(), e.g. in the GeoInit flight plan block.

Definition at line 234 of file nav.h.

#define GetPosAlt ( )    (stateGetPositionUtm_f()->alt)

Get current altitude above MSL.

Definition at line 227 of file nav.h.

Referenced by max7456_periodic().

#define GetPosX ( )    (stateGetPositionEnu_f()->x)

Get current x (east) position in local coordinates.

Definition at line 223 of file nav.h.

#define GetPosY ( )    (stateGetPositionEnu_f()->y)

Get current y (north) position in local coordinates.

Definition at line 225 of file nav.h.

#define HORIZONTAL_MODE_CIRCLE   2

Definition at line 86 of file nav.h.

Referenced by mission_nav_circle(), nav_circle(), nav_circle_XY(), and send_nav_status().

#define HORIZONTAL_MODE_WAYPOINT   0

Definition at line 84 of file nav.h.

Referenced by mission_nav_wp(), nav_home(), and nav_init().

#define NAV_GRAVITY   9.806

Definition at line 44 of file nav.h.

Referenced by nav_circle_XY().

#define nav_IncreaseShift (   x)    { if (x==0) nav_shift = 0; else nav_shift += x; }

Definition at line 216 of file nav.h.

#define NAV_MODE_COURSE   2

Definition at line 80 of file nav.h.

Referenced by fly_to_xy(), nav_circle_XY(), and nav_init().

#define NAV_MODE_ROLL   1

Definition at line 79 of file nav.h.

#define nav_SetNavRadius (   x)    { if (x==1) nav_radius = DEFAULT_CIRCLE_RADIUS; else if (x==-1) nav_radius = -DEFAULT_CIRCLE_RADIUS; else nav_radius = x; }

Definition at line 218 of file nav.h.

#define NavApproaching (   wp,
  time 
)    nav_approaching_xy(waypoints[wp].x, waypoints[wp].y, last_x, last_y, time)

Definition at line 164 of file nav.h.

Referenced by nav_anemotaxis().

#define NavApproachingFrom (   wp,
  from,
  time 
)    nav_approaching_xy(waypoints[wp].x, waypoints[wp].y, waypoints[from].x, waypoints[from].y, time)

Definition at line 165 of file nav.h.

Referenced by nav_line_border_run(), nav_line_run(), and nav_vertical_raster_run().

#define NavAttitude (   _roll)
Value:
{ \
{h_ctl_roll_setpoint = _roll;} \
}
uint8_t pprz_mode
Definition: autopilot.c:41
uint8_t lateral_mode
Definition: autopilot.c:50
#define PPRZ_MODE_AUTO1
Definition: autopilot.h:51
float h_ctl_roll_setpoint
#define LATERAL_MODE_ROLL
Definition: autopilot.h:76
if(PrimarySpektrumState.SpektrumTimer)

Definition at line 207 of file nav.h.

Referenced by nav_catapult_run(), and nav_launcher_run().

#define NavCircleCount ( )    (fabs(nav_circle_radians) / (2*M_PI))

Definition at line 148 of file nav.h.

Referenced by nav_line_osam_run(), nav_skid_landing_run(), and nav_survey_poly_osam_run().

#define NavCircleCountNoRewind ( )    (nav_circle_radians_no_rewind / (2*M_PI))

Definition at line 147 of file nav.h.

Referenced by nav_survey_poly_osam_run().

#define NavCircleQdr ( )    ({ float qdr = DegOfRad(M_PI_2 - nav_circle_trigo_qdr); NormCourse(qdr); qdr; })

Definition at line 149 of file nav.h.

#define NavCircleWaypoint (   wp,
  radius 
)    nav_circle_XY(waypoints[wp].x, waypoints[wp].y, radius)
#define NavCourseCloseTo (   x)    CloseDegAngles(x, DegOfRad(stateGetHorizontalSpeedDir_f()))

Definition at line 156 of file nav.h.

Referenced by nav_survey_polygon_run(), nav_survey_rectangle(), and nav_survey_zamboni_run().

#define NavFollow (   _ac_id,
  _distance,
  _height 
)    nav_follow(_ac_id, _distance, _height)

Definition at line 132 of file nav.h.

#define NavGlide (   _start_wp,
  _wp 
)    nav_glide(_start_wp, _wp)

Definition at line 135 of file nav.h.

#define NavGotoWaypoint (   _wp)
Value:
{ \
fly_to_xy(waypoints[_wp].x, waypoints[_wp].y); \
}
struct point waypoints[NB_WAYPOINT]
size == nb_waypoint, waypoint 0 is a dummy waypoint
Definition: common_nav.c:38

Definition at line 90 of file nav.h.

Referenced by nav_catapult_run().

#define NavHeading (   _course)
Value:
{ \
}
float h_ctl_course_setpoint
uint8_t lateral_mode
Definition: autopilot.c:50
#define LATERAL_MODE_COURSE
Definition: autopilot.h:77

Definition at line 202 of file nav.h.

#define NavKillThrottle ( )    { kill_throttle = 1; }

Definition at line 220 of file nav.h.

#define NavQdrCloseTo (   x)    CloseDegAngles(x, NavCircleQdr())
#define NavSegment (   _start,
  _end 
)    nav_route_xy(waypoints[_start].x, waypoints[_start].y, waypoints[_end].x, waypoints[_end].y)
#define NavSetManual (   _roll,
  _pitch,
  _yaw 
)    _Pragma("GCC error \"Manual mode in flight plan for fixedwing is not available\"")

Definition at line 213 of file nav.h.

#define NavVerticalAutoPitchMode (   _throttle)
Value:
{ \
nav_throttle_setpoint = _throttle; \
}
uint8_t v_ctl_climb_mode
Definition: energy_ctrl.c:75
#define V_CTL_CLIMB_MODE_AUTO_PITCH

Set the climb control to auto-pitch with the specified throttle pre-command.

Definition at line 177 of file nav.h.

#define NavVerticalClimbMode (   _climb)
Value:
{ \
}
float v_ctl_climb_setpoint
Definition: energy_ctrl.c:98
uint8_t v_ctl_mode
Definition: energy_ctrl.c:74
#define V_CTL_MODE_AUTO_CLIMB

Set the vertical mode to climb control with the specified climb setpoint.

Definition at line 191 of file nav.h.

Referenced by potential_task().

#define NavVerticalThrottleMode (   _throttle)
Value:
{ \
nav_throttle_setpoint = _throttle; \
}
#define V_CTL_MODE_AUTO_THROTTLE
uint8_t v_ctl_mode
Definition: energy_ctrl.c:74

Set the vertical mode to fixed throttle with the specified setpoint.

Definition at line 197 of file nav.h.

Referenced by nav_bungee_takeoff_run(), nav_catapult_highrate_module(), nav_catapult_run(), and nav_launcher_run().

#define NormCourse (   x)
Value:
{ \
uint8_t dont_loop_forever = 0; \
while (x < 0 && ++dont_loop_forever) x += 360; \
while (x >= 360 && ++dont_loop_forever) x -= 360; \
}
unsigned char uint8_t
Definition: types.h:14

Normalize a degree angle between 0 and 359.

Definition at line 141 of file nav.h.

#define Oval (   a,
  b,
 
)    nav_oval((b), (a), (c))

Definition at line 103 of file nav.h.

#define PowerVoltage ( )    (vsupply/10.)

Definition at line 48 of file nav.h.

#define RCLost ( )    bit_is_set(imcu_get_status(), STATUS_RADIO_REALLY_LOST)

Definition at line 129 of file nav.h.

#define RcRoll (   travel)    (imcu_get_radio(RADIO_ROLL) * (float)travel /(float)MAX_PPRZ)

Definition at line 49 of file nav.h.

#define SEND_NAVIGATION (   _trans,
  _dev 
)
Value:
{ \
uint8_t _circle_count = NavCircleCount(); \
struct EnuCoor_f* pos = stateGetPositionEnu_f(); \
float dist_wp = sqrtf(dist2_to_wp); \
float dist_home = sqrtf(dist2_to_home); \
pprz_msg_send_NAVIGATION(_trans, _dev, AC_ID, &nav_block, &nav_stage, &(pos->x), &(pos->y), &dist_wp, &dist_home, &_circle_count, &nav_oval_count); \
}
vector in East North Up coordinates Units: meters
uint8_t nav_block
static struct EnuCoor_f * stateGetPositionEnu_f(void)
Get position in local ENU coordinates (float).
Definition: state.h:713
uint8_t nav_stage
unsigned char uint8_t
Definition: types.h:14

Definition at line 237 of file nav.h.

Referenced by firmware_parse_msg(), navigation_task(), and send_nav().

#define Square (   _x)    ((_x)*(_x))

Definition at line 45 of file nav.h.

Referenced by monitor_task(), and nav_circle_XY().

Enumeration Type Documentation

Enumerator
OR12 
OC2 
OR21 
OC1 
OR12 
OC2 
OR21 
OC1 

Definition at line 52 of file nav.h.

Function Documentation

bool DownlinkSendWpNr ( uint8_t  _wp)

Definition at line 488 of file nav.c.

References DefaultChannel, DefaultDevice, and DownlinkSendWp.

void fly_to_xy ( float  x,
float  y 
)

Computes desired_x, desired_y and desired_course.

Definition at line 360 of file nav.c.

References CARROT, h_ctl_course_pgain, h_ctl_course_setpoint, h_ctl_roll_max_setpoint, h_ctl_roll_setpoint, lateral_mode, LATERAL_MODE_COURSE, LATERAL_MODE_ROLL, NAV_MODE_COURSE, stateGetHorizontalSpeedDir_f(), stateGetHorizontalSpeedNorm_f(), stateGetPositionEnu_f(), EnuCoor_f::x, and EnuCoor_f::y.

Referenced by formation_flight(), mission_nav_wp(), nav_circle_XY(), nav_route_xy(), and potential_task().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

bool nav_approaching_xy ( float  x,
float  y,
float  from_x,
float  from_y,
float  approaching_time 
)

Decide if the UAV is approaching the current waypoint.

Computes dist2_to_wp and compare it to square carrot. Return true if it is smaller. Else computes by scalar products if uav has not gone past waypoint. approaching_time can be negative and in this case, the UAV will fly after the waypoint for the given number of seconds.

Returns
true if the position (x, y) is reached

distance to waypoint in x

distance to waypoint in y

Definition at line 328 of file nav.c.

References dist2_to_wp, Max, stateGetHorizontalSpeedNorm_f(), stateGetPositionEnu_f(), EnuCoor_f::x, and EnuCoor_f::y.

Referenced by mission_nav_path(), mission_nav_segment(), mission_nav_wp(), nav_catapult_run(), nav_eight(), nav_line_osam_run(), nav_oval(), nav_spiral_run(), nav_survey_disc_run(), nav_survey_poly_osam_run(), nav_survey_polygon_run(), nav_survey_zamboni_run(), and snav_route().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

void nav_circle_XY ( float  x,
float  y,
float  radius 
)

Angle from center to mobile.

Angle from center to mobile.

Clockwise iff radius > 0

Computes a prebank. Go straight if inside or outside the circle

Definition at line 109 of file nav.c.

References CARROT, DistanceSquare, fly_to_xy(), HORIZONTAL_MODE_CIRCLE, Max, Min, nav_circle_trigo_qdr, NAV_GRAVITY, NAV_MODE_COURSE, nav_shift, radius, Square, stateGetHorizontalSpeedNorm_f(), stateGetPositionEnu_f(), EnuCoor_f::x, and EnuCoor_f::y.

Referenced by mission_nav_circle(), nav_eight(), nav_flower_run(), nav_launcher_run(), nav_line_border_run(), nav_line_osam_run(), nav_line_run(), nav_oval(), nav_skid_landing_run(), nav_spiral_run(), nav_survey_disc_run(), nav_survey_poly_osam_run(), nav_survey_polygon_run(), nav_survey_zamboni_run(), nav_vertical_raster_run(), snav_circle1(), snav_circle2(), and snav_on_time().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

bool nav_compute_baseleg ( uint8_t  wp_af,
uint8_t  wp_td,
uint8_t  wp_baseleg,
float  radius 
)

Definition at line 218 of file nav.c.

References point::a, nav_radius, radius, waypoints, point::x, and point::y.

bool nav_compute_final_from_glide ( uint8_t  wp_af,
uint8_t  wp_td,
float  glide 
)

Definition at line 241 of file nav.c.

References point::a, waypoints, point::x, and point::y.

void nav_eight ( uint8_t  target,
uint8_t  c1,
float  radius 
)

Navigation along a figure 8.

The cross center is defined by the waypoint [target], the center of one of the circles is defined by [c1]. Altitude is given by [target]. The navigation goes through 6 states: C1 (circle around [c1]), R1T, RT2 (route from circle 1 to circle 2 over [target]), C2 and R2T, RT1. If necessary, the [c1] waypoint is moved in the direction of [target] to be not far than [2*radius].

Definition at line 594 of file nav.c.

References point::a, c1, C1, C2, CARROT, InitStage, Max, nav_approaching_xy(), nav_circle_XY(), nav_route_xy(), NavCircleWaypoint, NavQdrCloseTo, R1T, R2T, RT1, RT2, target, waypoints, point::x, and point::y.

+ Here is the call graph for this function:

void nav_eight_init ( void  )

Definition at line 581 of file nav.c.

References C1.

void nav_follow ( uint8_t  _ac_id,
float  _distance,
float  _height 
)

Definition at line 305 of file nav.c.

void nav_glide ( uint8_t  start_wp,
uint8_t  wp 
)

Definition at line 158 of file nav.c.

References point::a, nav_leg_length, NavVerticalAltitudeMode, stateGetHorizontalSpeedNorm_f(), and waypoints.

+ Here is the call graph for this function:

void nav_home ( void  )

Home mode navigation (circle around HOME)

Home mode navigation (circle around HOME)

Nominal speed

Definition at line 427 of file nav.c.

void nav_init ( void  )

Navigation Initialisation.

Definition at line 523 of file nav.c.

void nav_oval ( uint8_t  ,
uint8_t  ,
float   
)

Definition at line 723 of file nav.c.

void nav_oval_init ( void  )

Definition at line 717 of file nav.c.

void nav_periodic_task ( void  )

Navigation main: call to the code generated from the XML flight plan.

Definition at line 443 of file nav.c.

void nav_route_xy ( float  last_wp_x,
float  last_wp_y,
float  wp_x,
float  wp_y 
)

Computes the carrot position along the desired segment.

distance of carrot (in meter)

Definition at line 386 of file nav.c.

References CARROT, fly_to_xy(), HORIZONTAL_MODE_ROUTE, Max, stateGetPositionEnu_f(), EnuCoor_f::x, and EnuCoor_f::y.

Referenced by mission_nav_path(), mission_nav_segment(), nav_bungee_takeoff_run(), nav_eight(), nav_flower_run(), nav_launcher_run(), nav_line_osam_run(), nav_oval(), nav_points(), nav_skid_landing_run(), nav_spiral_run(), nav_survey_disc_run(), nav_survey_losange_carto(), nav_survey_poly_osam_run(), nav_survey_rectangle(), nav_survey_zamboni_run(), and snav_route().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

void nav_without_gps ( void  )

Failsafe navigation without position estimation.

Just set attitude and throttle to FAILSAFE values to prevent the plane from crashing.

Definition at line 558 of file nav.c.

References h_ctl_roll_setpoint, lateral_mode, LATERAL_MODE_ROLL, MAX_PPRZ, TRIM_UPPRZ, v_ctl_mode, and V_CTL_MODE_AUTO_THROTTLE.

Referenced by navigation_task().

+ Here is the caller graph for this function:

Variable Documentation

float baseleg_out_qdr

Definition at line 217 of file nav.c.

float carrot_x

Definition at line 51 of file nav.c.

float carrot_y

Definition at line 51 of file nav.c.

float cur_pos_x
float cur_pos_y
float desired_x

Definition at line 311 of file nav.c.

Referenced by cam_segment_periodic(), formation_flight(), potential_task(), and send_desired().

float desired_y

Definition at line 311 of file nav.c.

Referenced by cam_segment_periodic(), formation_flight(), potential_task(), and send_desired().

float flight_altitude

Dynamically adjustable, reset to nav_altitude when it is changing.

Definition at line 75 of file nav.c.

float fp_climb

Definition at line 316 of file nav.c.

float fp_pitch

Definition at line 314 of file nav.c.

float fp_throttle

Definition at line 315 of file nav.c.

uint8_t horizontal_mode

Definition at line 71 of file nav.c.

uint8_t last_wp

Index of last waypoint.

Used only in "go" stage in "route" horiz mode

Definition at line 48 of file nav.c.

float last_x

Definition at line 45 of file nav.c.

Referenced by nav_survey_polygon_run().

float last_y

Definition at line 45 of file nav.c.

Referenced by nav_survey_polygon_run().

float nav_altitude

Definition at line 310 of file nav.c.

float nav_circle_radians

Status on the current circle.

Definition at line 54 of file nav.c.

float nav_circle_radians_no_rewind

Definition at line 55 of file nav.c.

float nav_circle_radius

Definition at line 69 of file nav.c.

float nav_circle_trigo_qdr

Definition at line 56 of file nav.c.

Referenced by nav_circle_XY().

float nav_circle_x

Definition at line 69 of file nav.c.

Referenced by flight_benchmark_periodic().

float nav_circle_y

Definition at line 69 of file nav.c.

Referenced by flight_benchmark_periodic().

float nav_climb

Definition at line 57 of file nav.c.

float nav_course

Definition at line 57 of file nav.c.

float nav_glide_pitch_trim

Definition at line 77 of file nav.c.

float nav_ground_speed_pgain

Definition at line 84 of file nav.c.

float nav_ground_speed_setpoint

Definition at line 84 of file nav.c.

bool nav_in_circle

Definition at line 67 of file nav.c.

Referenced by nav_survey_rectangle(), and nav_survey_rectangle_rotorcraft_run().

bool nav_in_segment

Definition at line 68 of file nav.c.

Referenced by nav_survey_rectangle(), and nav_survey_rectangle_rotorcraft_run().

int nav_mode

Definition at line 91 of file nav.c.

uint8_t nav_oval_count

Navigation along a figure O.

One side leg is defined by waypoints [p1] and [p2]. The navigation goes through 4 states: OC1 (half circle next to [p1]), OR21 (route [p2] to [p1], OC2 (half circle next to [p2]) and OR12 (opposite leg).

Initial state is the route along the desired segment (OC2).

Definition at line 715 of file nav.c.

float nav_pitch

Definition at line 313 of file nav.c.

float nav_radius

Definition at line 57 of file nav.c.

float nav_segment_x_1

Definition at line 70 of file nav.c.

Referenced by flight_benchmark_periodic().

float nav_segment_x_2

Definition at line 70 of file nav.c.

Referenced by flight_benchmark_periodic().

float nav_segment_y_1

Definition at line 70 of file nav.c.

Referenced by flight_benchmark_periodic().

float nav_segment_y_2

Definition at line 70 of file nav.c.

Referenced by flight_benchmark_periodic().

float nav_shift

Definition at line 57 of file nav.c.

Referenced by nav_circle_XY().

bool nav_survey_active

Definition at line 89 of file nav.c.

pprz_t nav_throttle_setpoint

Definition at line 312 of file nav.c.

Referenced by attitude_loop().

float rc_pitch

Definition at line 50 of file nav.c.