Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
nav.h File Reference
+ 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()   (ap_electrical.vsupply)
 
#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()   { autopilot_set_kill_throttle(true); }
 
#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)
 

Enumerations

enum  oval_status {
  OR12, OC2, OR21, OC1,
  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)
 Navigation along a figure O. More...
 
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...
 
void nav_compute_baseleg (uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, float radius)
 
void 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...
 
void DownlinkSendWpNr (uint8_t _wp)
 

Variables

enum oval_status oval_status
 
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
 with INT32_ANGLE_FRAC More...
 
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

◆ CloseDegAngles

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

Definition at line 152 of file nav.h.

◆ DistanceSquare

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

Definition at line 47 of file nav.h.

◆ Eight

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

Definition at line 99 of file nav.h.

◆ GetAltRef

#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 235 of file nav.h.

◆ GetPosAlt

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

Get current altitude above MSL.

Definition at line 228 of file nav.h.

◆ GetPosX

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

Get current x (east) position in local coordinates.

Definition at line 224 of file nav.h.

◆ GetPosY

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

Get current y (north) position in local coordinates.

Definition at line 226 of file nav.h.

◆ HORIZONTAL_MODE_CIRCLE

#define HORIZONTAL_MODE_CIRCLE   2

Definition at line 87 of file nav.h.

◆ HORIZONTAL_MODE_ROUTE

#define HORIZONTAL_MODE_ROUTE   1

Definition at line 86 of file nav.h.

◆ HORIZONTAL_MODE_WAYPOINT

#define HORIZONTAL_MODE_WAYPOINT   0

Definition at line 85 of file nav.h.

◆ NAV_GRAVITY

#define NAV_GRAVITY   9.806

Definition at line 45 of file nav.h.

◆ nav_IncreaseShift

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

Definition at line 217 of file nav.h.

◆ NAV_MODE_COURSE

#define NAV_MODE_COURSE   2

Definition at line 81 of file nav.h.

◆ NAV_MODE_ROLL

#define NAV_MODE_ROLL   1

Definition at line 80 of file nav.h.

◆ nav_SetNavRadius

#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 219 of file nav.h.

◆ NavApproaching

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

Definition at line 165 of file nav.h.

◆ NavApproachingFrom

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

Definition at line 166 of file nav.h.

◆ NavAttitude

#define NavAttitude (   _roll)
Value:
{ \
lateral_mode = LATERAL_MODE_ROLL; \
{h_ctl_roll_setpoint = _roll;} \
}

Definition at line 208 of file nav.h.

◆ NavCircleCount

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

Definition at line 149 of file nav.h.

◆ NavCircleCountNoRewind

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

Definition at line 148 of file nav.h.

◆ NavCircleQdr

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

Definition at line 150 of file nav.h.

◆ NavCircleWaypoint

#define NavCircleWaypoint (   wp,
  radius 
)    nav_circle_XY(waypoints[wp].x, waypoints[wp].y, radius)

Definition at line 138 of file nav.h.

◆ NavCourseCloseTo

#define NavCourseCloseTo (   x)    CloseDegAngles(x, DegOfRad(stateGetHorizontalSpeedDir_f()))

Definition at line 157 of file nav.h.

◆ NavFollow

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

Definition at line 133 of file nav.h.

◆ NavGlide

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

Definition at line 136 of file nav.h.

◆ NavGotoWaypoint

#define NavGotoWaypoint (   _wp)
Value:
{ \
horizontal_mode = HORIZONTAL_MODE_WAYPOINT; \
fly_to_xy(waypoints[_wp].x, waypoints[_wp].y); \
}

Definition at line 91 of file nav.h.

◆ NavHeading

#define NavHeading (   _course)
Value:
{ \
lateral_mode = LATERAL_MODE_COURSE; \
h_ctl_course_setpoint = _course; \
}

Definition at line 203 of file nav.h.

◆ NavKillThrottle

#define NavKillThrottle ( )    { autopilot_set_kill_throttle(true); }

Definition at line 221 of file nav.h.

◆ NavQdrCloseTo

#define NavQdrCloseTo (   x)    CloseDegAngles(x, NavCircleQdr())

True if x (in degrees) is close to the current QDR (less than 10 degrees)

Definition at line 155 of file nav.h.

◆ NavSegment

#define NavSegment (   _start,
  _end 
)    nav_route_xy(waypoints[_start].x, waypoints[_start].y, waypoints[_end].x, waypoints[_end].y)

Definition at line 161 of file nav.h.

◆ NavSetManual

#define NavSetManual (   _roll,
  _pitch,
  _yaw 
)    _Pragma("GCC error \"Manual mode in flight plan for fixedwing is not available\"")

Definition at line 214 of file nav.h.

◆ NavVerticalAltitudeMode

#define NavVerticalAltitudeMode (   _alt,
  _pre_climb 
)
Value:
{ \
v_ctl_mode = V_CTL_MODE_AUTO_ALT; \
nav_altitude = _alt; \
v_ctl_altitude_pre_climb = _pre_climb; \
}

Set the vertical mode to altitude control with the specified altitude setpoint and climb pre-command.

Definition at line 185 of file nav.h.

◆ NavVerticalAutoPitchMode

#define NavVerticalAutoPitchMode (   _throttle)
Value:
{ \
v_ctl_climb_mode = V_CTL_CLIMB_MODE_AUTO_PITCH; \
nav_throttle_setpoint = _throttle; \
}

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

Definition at line 178 of file nav.h.

◆ NavVerticalAutoThrottleMode

#define NavVerticalAutoThrottleMode (   _pitch)
Value:
{ \
v_ctl_climb_mode = V_CTL_CLIMB_MODE_AUTO_THROTTLE; \
nav_pitch = _pitch; \
}

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

Definition at line 171 of file nav.h.

◆ NavVerticalClimbMode

#define NavVerticalClimbMode (   _climb)
Value:
{ \
v_ctl_mode = V_CTL_MODE_AUTO_CLIMB; \
v_ctl_climb_setpoint = _climb; \
}

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

Definition at line 192 of file nav.h.

◆ NavVerticalThrottleMode

#define NavVerticalThrottleMode (   _throttle)
Value:
{ \
v_ctl_mode = V_CTL_MODE_AUTO_THROTTLE; \
nav_throttle_setpoint = _throttle; \
}

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

Definition at line 198 of file nav.h.

◆ NormCourse

#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; \
}

Normalize a degree angle between 0 and 359.

Definition at line 142 of file nav.h.

◆ Oval

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

Definition at line 104 of file nav.h.

◆ PowerVoltage

#define PowerVoltage ( )    (ap_electrical.vsupply)

Definition at line 49 of file nav.h.

◆ RCLost

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

Definition at line 130 of file nav.h.

◆ RcRoll

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

Definition at line 50 of file nav.h.

◆ SEND_NAVIGATION

#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); \
uint8_t kill = (uint8_t)autopilot.kill_throttle; \
pprz_msg_send_NAVIGATION(_trans, _dev, AC_ID, &nav_block, &nav_stage, &(pos->x), &(pos->y), &dist_wp, &dist_home, &autopilot.flight_time, &block_time, &stage_time, &kill, &_circle_count, &nav_oval_count); \
}

Definition at line 238 of file nav.h.

◆ Square

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

Definition at line 46 of file nav.h.

Enumeration Type Documentation

◆ oval_status

Enumerator
OR12 
OC2 
OR21 
OC1 
OR12 
OC2 
OR21 
OC1 
OR12 
OC2 
OR21 
OC1 

Definition at line 53 of file nav.h.

Function Documentation

◆ DownlinkSendWpNr()

void DownlinkSendWpNr ( uint8_t  _wp)

Definition at line 495 of file nav.c.

References DefaultChannel, DefaultDevice, DownlinkSendWp(), and nb_waypoint.

Referenced by nav_catapult_run().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ fly_to_xy()

void fly_to_xy ( float  x,
float  y 
)

◆ nav_approaching_xy()

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 323 of file nav.c.

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

Referenced by gvf_nav_survey_polygon_run(), 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:

◆ nav_circle_XY()

◆ nav_compute_baseleg()

void 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, baseleg_out_qdr, nav_radius, waypoints, point::x, and point::y.

◆ nav_compute_final_from_glide()

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

Definition at line 239 of file nav.c.

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

◆ nav_eight()

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 604 of file nav.c.

References point::a, c1, C1, c2, 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:

◆ nav_eight_init()

void nav_eight_init ( void  )

Definition at line 591 of file nav.c.

References C1.

◆ nav_follow()

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

Definition at line 300 of file nav.c.

◆ nav_glide()

void nav_glide ( uint8_t  start_wp,
uint8_t  wp 
)

Definition at line 158 of file nav.c.

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

+ Here is the call graph for this function:

◆ nav_home()

void nav_home ( void  )

Home mode navigation (circle around HOME)

Home mode navigation (circle around HOME)

Nominal speed

Definition at line 422 of file nav.c.

◆ nav_init()

void nav_init ( void  )

Navigation Initialisation.

Definition at line 530 of file nav.c.

◆ nav_oval()

void nav_oval ( uint8_t  p1,
uint8_t  p2,
float  radius 
)

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 733 of file nav.c.

◆ nav_oval_init()

void nav_oval_init ( void  )

Definition at line 727 of file nav.c.

◆ nav_periodic_task()

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.

◆ nav_route_xy()

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

◆ nav_without_gps()

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 568 of file nav.c.

References h_ctl_roll_setpoint, lateral_mode, LATERAL_MODE_ROLL, MAX_PPRZ, nav_pitch, nav_throttle_setpoint, 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

◆ baseleg_out_qdr

float baseleg_out_qdr

Definition at line 217 of file nav.c.

Referenced by nav_compute_baseleg().

◆ carrot_x

float carrot_x

Definition at line 51 of file nav.c.

◆ carrot_y

float carrot_y

Definition at line 68 of file nav.h.

◆ cur_pos_x

float cur_pos_x

◆ cur_pos_y

float cur_pos_y

◆ desired_x

float desired_x

◆ desired_y

float desired_y

Definition at line 59 of file nav.h.

◆ flight_altitude

float flight_altitude

Dynamically adjustable, reset to nav_altitude when it is changing.

Definition at line 59 of file nav.h.

◆ fp_climb

float fp_climb

Definition at line 311 of file nav.c.

Referenced by nav_init().

◆ fp_pitch

float fp_pitch

Definition at line 309 of file nav.c.

Referenced by nav_init().

◆ fp_throttle

float fp_throttle

Definition at line 310 of file nav.c.

Referenced by nav_init().

◆ horizontal_mode

uint8_t horizontal_mode

Definition at line 71 of file nav.c.

◆ last_wp

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.

◆ last_x

float last_x

Definition at line 45 of file nav.c.

Referenced by gvf_nav_survey_polygon_run(), nav_init_stage(), and nav_survey_polygon_run().

◆ last_y

float last_y

Definition at line 57 of file nav.h.

◆ nav_altitude

float nav_altitude

Definition at line 59 of file nav.h.

◆ nav_circle_radians

float nav_circle_radians

Status on the current circle.

Definition at line 54 of file nav.c.

Referenced by nav_circle(), nav_circle_XY(), and nav_init_stage().

◆ nav_circle_radians_no_rewind

float nav_circle_radians_no_rewind

Definition at line 55 of file nav.c.

Referenced by nav_circle_XY(), and nav_init_stage().

◆ nav_circle_radius

float nav_circle_radius

Definition at line 74 of file nav.h.

◆ nav_circle_trigo_qdr

float nav_circle_trigo_qdr

Definition at line 56 of file nav.c.

Referenced by nav_circle_XY().

◆ nav_circle_x

float nav_circle_x

Definition at line 69 of file nav.c.

Referenced by flight_benchmark_periodic(), nav_circle_XY(), and send_circle().

◆ nav_circle_y

float nav_circle_y

Definition at line 74 of file nav.h.

◆ nav_climb

float nav_climb

Definition at line 57 of file nav.c.

◆ nav_course

float nav_course

Definition at line 57 of file nav.c.

◆ nav_glide_pitch_trim

float nav_glide_pitch_trim

Definition at line 59 of file nav.h.

◆ nav_ground_speed_pgain

float nav_ground_speed_pgain

Definition at line 84 of file nav.c.

Referenced by nav_init().

◆ nav_ground_speed_setpoint

float nav_ground_speed_setpoint

Definition at line 111 of file nav.h.

◆ nav_in_circle

◆ nav_in_segment

bool nav_in_segment

◆ nav_mode

int nav_mode

Definition at line 91 of file nav.c.

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

◆ nav_oval_count

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 725 of file nav.c.

◆ nav_pitch

◆ nav_radius

float nav_radius

Definition at line 57 of file nav.c.

◆ nav_segment_x_1

float nav_segment_x_1

Definition at line 70 of file nav.c.

Referenced by flight_benchmark_periodic(), nav_route_xy(), and send_segment().

◆ nav_segment_x_2

float nav_segment_x_2

Definition at line 75 of file nav.h.

◆ nav_segment_y_1

float nav_segment_y_1

Definition at line 75 of file nav.h.

◆ nav_segment_y_2

float nav_segment_y_2

Definition at line 75 of file nav.h.

◆ nav_shift

float nav_shift

Definition at line 57 of file nav.c.

Referenced by nav_circle_XY(), nav_init_stage(), and nav_route_xy().

◆ nav_survey_active

bool nav_survey_active

Definition at line 89 of file nav.c.

◆ nav_survey_east

float nav_survey_east

Definition at line 115 of file nav.h.

◆ nav_survey_north

float nav_survey_north

Definition at line 115 of file nav.h.

◆ nav_survey_shift

◆ nav_survey_south

float nav_survey_south

Definition at line 115 of file nav.h.

◆ nav_survey_west

◆ nav_throttle_setpoint

pprz_t nav_throttle_setpoint

Definition at line 307 of file nav.c.

Referenced by attitude_loop(), nav_without_gps(), and v_ctl_guidance_loop().

◆ oval_status

Definition at line 43 of file nav.c.

◆ rc_pitch

float rc_pitch

Definition at line 50 of file nav.c.

block_time
uint16_t block_time
Definition: common_flight_plan.c:33
V_CTL_MODE_AUTO_ALT
#define V_CTL_MODE_AUTO_ALT
Definition: guidance_common.h:39
V_CTL_CLIMB_MODE_AUTO_THROTTLE
#define V_CTL_CLIMB_MODE_AUTO_THROTTLE
Definition: guidance_common.h:47
dist2_to_home
float dist2_to_home
squared distance to home waypoint
Definition: navigation.c:86
pprz_autopilot::flight_time
uint16_t flight_time
flight time in seconds
Definition: autopilot.h:65
LATERAL_MODE_ROLL
#define LATERAL_MODE_ROLL
Definition: autopilot_firmware.h:38
stateGetPositionEnu_f
static struct EnuCoor_f * stateGetPositionEnu_f(void)
Get position in local ENU coordinates (float).
Definition: state.h:719
nav_stage
uint8_t nav_stage
Definition: common_flight_plan.c:35
waypoints
struct point waypoints[NB_WAYPOINT]
size == nb_waypoint, waypoint 0 is a dummy waypoint
Definition: common_nav.c:38
h_ctl_roll_setpoint
float h_ctl_roll_setpoint
Definition: stabilization_adaptive.c:157
nav_oval_count
uint8_t nav_oval_count
Navigation along a figure O.
Definition: nav.c:725
HORIZONTAL_MODE_WAYPOINT
#define HORIZONTAL_MODE_WAYPOINT
Definition: nav.h:85
autopilot
struct pprz_autopilot autopilot
Global autopilot structure.
Definition: autopilot.c:50
V_CTL_CLIMB_MODE_AUTO_PITCH
#define V_CTL_CLIMB_MODE_AUTO_PITCH
Definition: guidance_common.h:48
NavCircleCount
#define NavCircleCount()
Definition: nav.h:149
nav_block
uint8_t nav_block
Definition: common_flight_plan.c:35
uint8_t
unsigned char uint8_t
Definition: types.h:14
EnuCoor_f
vector in East North Up coordinates Units: meters
Definition: pprz_geodetic_float.h:72
stage_time
uint16_t stage_time
In s.
Definition: common_flight_plan.c:33
V_CTL_MODE_AUTO_THROTTLE
#define V_CTL_MODE_AUTO_THROTTLE
Definition: guidance_common.h:37
LATERAL_MODE_COURSE
#define LATERAL_MODE_COURSE
Definition: autopilot_firmware.h:39
autopilot_get_mode
uint8_t autopilot_get_mode(void)
get autopilot mode
Definition: autopilot.c:184
V_CTL_MODE_AUTO_CLIMB
#define V_CTL_MODE_AUTO_CLIMB
Definition: guidance_common.h:38
pprz_autopilot::kill_throttle
bool kill_throttle
allow autopilot to use throttle
Definition: autopilot.h:69
dist2_to_wp
float dist2_to_wp
squared distance to next waypoint
Definition: navigation.c:89
AP_MODE_AUTO1
#define AP_MODE_AUTO1
Definition: autopilot_static.h:37