Paparazzi UAS
v5.10_stable-5-g83a0da5-dirty
Paparazzi is a free software Unmanned Aircraft System.
|
Fixedwing Navigation library. More...
#include "std.h"
#include "paparazzi.h"
#include "state.h"
#include "subsystems/navigation/nav_survey_rectangle.h"
#include "subsystems/navigation/common_flight_plan.h"
#include "subsystems/navigation/common_nav.h"
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) |
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.
#define CloseDegAngles | ( | _c1, | |
_c2 | |||
) | ({ float _diff = _c1 - _c2; NormCourse(_diff); 350 < _diff || _diff < 10; }) |
Definition at line 46 of file nav.h.
Referenced by nav_circle_XY().
#define DownlinkSendWp | ( | _trans, | |
_dev, | |||
i | |||
) |
Definition at line 247 of file nav.h.
Referenced by DownlinkSendWpNr(), nav_catapult_run(), and send_wp_moved().
#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.
#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) |
#define GetPosY | ( | ) | (stateGetPositionEnu_f()->y) |
#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_ROUTE 1 |
Definition at line 85 of file nav.h.
Referenced by mission_nav_path(), mission_nav_segment(), nav_route(), nav_route_xy(), nav_survey_poly_run(), nav_survey_rectangle_rotorcraft_run(), nav_survey_rectangle_rotorcraft_setup(), 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_MODE_COURSE 2 |
Definition at line 80 of file nav.h.
Referenced by fly_to_xy(), nav_circle_XY(), and nav_init().
#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 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 | ) |
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; }) |
#define NavCircleWaypoint | ( | wp, | |
radius | |||
) | nav_circle_XY(waypoints[wp].x, waypoints[wp].y, radius) |
Definition at line 137 of file nav.h.
Referenced by nav_anemotaxis(), nav_chemotaxis(), nav_eight(), nav_home(), nav_survey_losange_carto(), and nav_survey_rectangle().
#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) |
#define NavGotoWaypoint | ( | _wp | ) |
#define NavHeading | ( | _course | ) |
#define NavKillThrottle | ( | ) | { kill_throttle = 1; } |
#define NavQdrCloseTo | ( | x | ) | CloseDegAngles(x, NavCircleQdr()) |
True if x (in degrees) is close to the current QDR (less than 10 degrees)
Definition at line 154 of file nav.h.
Referenced by nav_anemotaxis(), nav_eight(), nav_line_border_run(), nav_line_osam_run(), nav_line_run(), nav_oval(), nav_skid_landing_run(), nav_survey_disc_run(), nav_survey_poly_osam_run(), nav_vertical_raster_run(), snav_circle1(), and snav_circle2().
#define NavSegment | ( | _start, | |
_end | |||
) | nav_route_xy(waypoints[_start].x, waypoints[_start].y, waypoints[_end].x, waypoints[_end].y) |
Definition at line 160 of file nav.h.
Referenced by gls_run(), nav_anemotaxis(), nav_line_border_run(), nav_line_run(), and nav_vertical_raster_run().
#define NavSetManual | ( | _roll, | |
_pitch, | |||
_yaw | |||
) | _Pragma("GCC error \"Manual mode in flight plan for fixedwing is not available\"") |
#define NavVerticalAltitudeMode | ( | _alt, | |
_pre_climb | |||
) |
Set the vertical mode to altitude control with the specified altitude setpoint and climb pre-command.
Definition at line 184 of file nav.h.
Referenced by gls_run(), mission_nav_circle(), mission_nav_path(), mission_nav_segment(), mission_nav_wp(), nav_catapult_run(), nav_flower_run(), nav_glide(), nav_launcher_run(), nav_line_border_run(), nav_line_osam_run(), nav_line_run(), nav_skid_landing_run(), nav_spiral_run(), nav_survey_disc_run(), nav_survey_poly_osam_run(), nav_survey_poly_setup(), nav_survey_polygon_run(), nav_survey_polygon_setup(), nav_survey_rectangle(), nav_survey_rectangle_rotorcraft_setup(), nav_survey_zamboni_run(), nav_survey_zamboni_setup(), nav_vertical_raster_run(), snav_circle1(), snav_circle2(), snav_on_time(), and snav_route().
#define NavVerticalAutoPitchMode | ( | _throttle | ) |
Set the climb control to auto-pitch with the specified throttle pre-command.
#define NavVerticalAutoThrottleMode | ( | _pitch | ) |
Set the climb control to auto-throttle with the specified pitch pre-command.
Definition at line 170 of file nav.h.
Referenced by formation_flight(), gls_run(), mission_nav_circle(), mission_nav_path(), mission_nav_segment(), mission_nav_wp(), nav_bungee_takeoff_run(), nav_catapult_run(), nav_flower_run(), nav_launcher_run(), nav_line_border_run(), nav_line_osam_run(), nav_line_run(), nav_skid_landing_run(), nav_spiral_run(), nav_survey_disc_run(), nav_survey_poly_osam_run(), nav_survey_polygon_run(), nav_survey_polygon_setup(), nav_survey_rectangle(), nav_survey_zamboni_run(), nav_survey_zamboni_setup(), nav_vertical_raster_run(), potential_task(), snav_circle1(), snav_circle2(), snav_on_time(), and snav_route().
#define NavVerticalClimbMode | ( | _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 | ) |
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 | ) |
#define RCLost | ( | ) | bit_is_set(imcu_get_status(), STATUS_RADIO_REALLY_LOST) |
#define RcRoll | ( | travel | ) | (imcu_get_radio(RADIO_ROLL) * (float)travel /(float)MAX_PPRZ) |
#define SEND_NAVIGATION | ( | _trans, | |
_dev | |||
) |
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().
enum oval_status |
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().
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.
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().
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().
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.
void nav_follow | ( | uint8_t | _ac_id, |
float | _distance, | ||
float | _height | ||
) |
Definition at line 158 of file nav.c.
References point::a, nav_leg_length, NavVerticalAltitudeMode, stateGetHorizontalSpeedNorm_f(), and waypoints.
void nav_home | ( | void | ) |
void nav_periodic_task | ( | void | ) |
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().
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().
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 |
uint8_t last_wp |
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_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().
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().
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).
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().
float nav_survey_east |
Definition at line 88 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), nav_survey_rectangle_rotorcraft_run(), and nav_survey_rectangle_rotorcraft_setup().
float nav_survey_north |
Definition at line 88 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), nav_survey_rectangle_rotorcraft_run(), and nav_survey_rectangle_rotorcraft_setup().
float nav_survey_shift |
Definition at line 87 of file nav.c.
Referenced by nav_survey_disc_run(), nav_survey_disc_setup(), nav_survey_rectangle(), nav_survey_rectangle_init(), and nav_survey_rectangle_rotorcraft_run().
float nav_survey_south |
Definition at line 88 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), nav_survey_rectangle_rotorcraft_run(), and nav_survey_rectangle_rotorcraft_setup().
float nav_survey_west |
Definition at line 88 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), nav_survey_rectangle_rotorcraft_run(), and nav_survey_rectangle_rotorcraft_setup().
pprz_t nav_throttle_setpoint |
Definition at line 312 of file nav.c.
Referenced by attitude_loop().