Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
Fixedwing functions to compute navigation. More...
#include <math.h>
#include "std.h"
#include "firmwares/fixedwing/nav.h"
#include "firmwares/fixedwing/stabilization/stabilization_attitude.h"
#include "autopilot.h"
#include "modules/gps/gps.h"
#include "generated/flight_plan.h"
#include "modules/nav/common_nav.c"
#include "modules/datalink/telemetry.h"
Go to the source code of this file.
Macros | |
#define | NAV_C |
#define | NAV_GLIDE_PITCH_TRIM 0. |
#define | MIN_DX ((int16_t)(MAX_PPRZ * 0.05)) |
#define | MAX_DIST_CARROT 250. |
#define | MIN_HEIGHT_CARROT 50. |
#define | MAX_HEIGHT_CARROT 150. |
#define | Goto3D(radius) |
#define | LINE_START_FUNCTION {} |
#define | LINE_STOP_FUNCTION {} |
#define | FAILSAFE_HOME_RADIUS DEFAULT_CIRCLE_RADIUS |
Enumerations | |
enum | eight_status { R1T , RT2 , C2 , R2T , RT1 , C1 } |
Functions | |
void | nav_init_stage (void) |
needs to be implemented by fixedwing and rotorcraft seperately More... | |
void | nav_circle_XY (float x, float y, float radius) |
Navigates around (x, y). More... | |
void | nav_glide (uint8_t start_wp, uint8_t wp) |
void | nav_glide_alt (float start_alt, float final_alt) |
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) |
static void | compute_TOD (uint8_t _af, uint8_t _td, uint8_t _tod, float glide_airspeed, float glide_vspeed) |
void | nav_follow (uint8_t _ac_id, float distance, float height) |
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 | fly_to_xy (float x, float y) |
Computes desired_x, desired_y and desired_course. More... | |
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... | |
static void | nav_set_altitude (void) |
void | nav_home (void) |
Home mode navigation (circle around HOME) More... | |
void | nav_periodic_task (void) |
Navigation main: call to the code generated from the XML flight plan. More... | |
static void | send_nav_ref (struct transport_tx *trans, struct link_device *dev) |
Periodic telemetry. More... | |
static void | send_nav (struct transport_tx *trans, struct link_device *dev) |
static void | DownlinkSendWp (struct transport_tx *trans, struct link_device *dev, uint8_t _wp) |
static void | send_wp_moved (struct transport_tx *trans, struct link_device *dev) |
void | DownlinkSendWpNr (uint8_t _wp) |
static void | send_circle (struct transport_tx *trans, struct link_device *dev) |
static void | send_segment (struct transport_tx *trans, struct link_device *dev) |
static void | send_survey (struct transport_tx *trans, struct link_device *dev) |
void | nav_init (void) |
Navigation Initialisation. More... | |
void | nav_without_gps (void) |
Failsafe navigation without position estimation. More... | |
void | nav_parse_BLOCK (struct link_device *dev, struct transport_tx *trans, uint8_t *buf) |
void | nav_parse_MOVE_WP (struct link_device *dev, struct transport_tx *trans, uint8_t *buf) |
void | nav_eight_init (void) |
void | nav_eight (uint8_t target, uint8_t c1, float radius) |
Navigation along a figure 8. More... | |
void | nav_oval_init (void) |
void | nav_oval (uint8_t p1, uint8_t p2, float radius) |
Fixedwing functions to compute navigation.
Definition in file nav.c.
#define FAILSAFE_HOME_RADIUS DEFAULT_CIRCLE_RADIUS |
#define Goto3D | ( | radius | ) |
enum eight_status |
|
inlinestatic |
Definition at line 261 of file nav.c.
References stateGetHorizontalWindspeed_f(), WaypointAlt, WaypointX, WaypointY, FloatVect2::x, and FloatVect2::y.
|
static |
Definition at line 482 of file nav.c.
References dev, nav_utm_east0, nav_utm_north0, nav_utm_zone0, waypoints, EnuCoor_f::x, point::x, EnuCoor_f::y, and point::y.
Referenced by DownlinkSendWpNr(), and send_wp_moved().
void DownlinkSendWpNr | ( | uint8_t | _wp | ) |
Definition at line 497 of file nav.c.
References DefaultChannel, DefaultDevice, DownlinkSendWp(), and nb_waypoint.
Referenced by nav_catapult_run().
void fly_to_xy | ( | float | x, |
float | y | ||
) |
Computes desired_x, desired_y and desired_course.
Definition at line 356 of file nav.c.
References CARROT, desired_x, desired_y, 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, NAV_MODE_COURSE, s, 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 325 of file nav.c.
References dist2_to_wp, 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_land_run(), nav_line_osam_run(), nav_oval(), nav_spiral_run(), nav_survey_poly_osam_run(), nav_survey_polygon_run(), nav_survey_zamboni_run(), nav_takeoff_run(), and snav_route().
void nav_circle_XY | ( | float | x, |
float | y, | ||
float | radius | ||
) |
Navigates around (x, y).
Angle from center to mobile.
Clockwise iff radius > 0
Computes a prebank. Go straight if inside or outside the circle
Definition at line 108 of file nav.c.
References CARROT, circle_bank, DistanceSquare, fly_to_xy(), horizontal_mode, HORIZONTAL_MODE_CIRCLE, Min, nav_circle_radians, nav_circle_radians_no_rewind, nav_circle_radius, nav_circle_trigo_qdr, nav_circle_x, nav_circle_y, NAV_GRAVITY, nav_in_circle, nav_in_segment, nav_mode, NAV_MODE_COURSE, nav_shift, 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_poly_osam_run(), nav_survey_polygon_run(), nav_survey_zamboni_run(), nav_vertical_raster_run(), snav_circle1(), snav_circle2(), and snav_on_time().
Definition at line 220 of file nav.c.
References point::a, baseleg_out_qdr, nav_radius, waypoints, point::x, and point::y.
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 633 of file nav.c.
References point::a, UtmCoor_f::alt, C1, c1, C2, c2, CARROT, InitStage, 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 nav_glide_alt(), and waypoints.
void nav_glide_alt | ( | float | start_alt, |
float | final_alt | ||
) |
Definition at line 163 of file nav.c.
References nav_leg_length, nav_leg_progress, NavVerticalAltitudeMode, and stateGetHorizontalSpeedNorm_f().
Referenced by nav_glide(), and nav_land_run().
void nav_home | ( | void | ) |
Home mode navigation (circle around HOME)
Nominal speed
Definition at line 424 of file nav.c.
References autopilot, compute_dist2_to_home(), dist2_to_home, dist2_to_wp, FAILSAFE_HOME_RADIUS, ground_alt, pprz_autopilot::launch, nav_altitude, nav_pitch, nav_set_altitude(), NavCircleWaypoint, v_ctl_mode, V_CTL_MODE_AUTO_ALT, V_CTL_MODE_AUTO_THROTTLE, and v_ctl_throttle_setpoint.
Referenced by autopilot_static_periodic(), and navigation_task().
void nav_init | ( | void | ) |
Navigation Initialisation.
Definition at line 532 of file nav.c.
References common_flight_plan_init(), DEFAULT_CIRCLE_RADIUS, DefaultPeriodic, fp_climb, fp_pitch, fp_throttle, ground_alt, nav_glide_pitch_trim, NAV_GLIDE_PITCH_TRIM, nav_ground_speed_pgain, nav_ground_speed_setpoint, nav_mode, NAV_MODE_COURSE, nav_radius, nav_survey_shift, register_periodic_telemetry(), send_circle(), send_nav(), send_nav_ref(), send_segment(), send_survey(), and send_wp_moved().
void nav_init_stage | ( | void | ) |
needs to be implemented by fixedwing and rotorcraft seperately
Definition at line 92 of file nav.c.
References last_x, last_y, nav_circle_radians, nav_circle_radians_no_rewind, nav_in_circle, nav_in_segment, nav_shift, stage_time, stateGetPositionEnu_f(), EnuCoor_f::x, and EnuCoor_f::y.
Referenced by gvf_nav_survey_polygon_run(), nav_bungee_takeoff_run(), nav_flower_run(), nav_line_border_run(), nav_line_osam_run(), nav_line_run(), nav_skid_landing_run(), nav_survey_hybrid_run(), nav_survey_poly_osam_run(), nav_survey_poly_run(), nav_survey_polygon_run(), nav_survey_zamboni_run(), and nav_vertical_raster_run().
Definition at line 762 of file nav.c.
References point::a, CARROT, InitStage, LINE_START_FUNCTION, LINE_STOP_FUNCTION, nav_approaching_xy(), nav_circle_XY(), nav_oval_count, nav_route_xy(), NavQdrCloseTo, OC1, OC2, OR12, OR21, waypoints, point::x, and point::y.
Referenced by nav_register_oval().
void nav_oval_init | ( | void | ) |
Definition at line 756 of file nav.c.
References nav_oval_count, and OC2.
Referenced by nav_register_oval().
void nav_parse_BLOCK | ( | struct link_device * | dev, |
struct transport_tx * | trans, | ||
uint8_t * | buf | ||
) |
Definition at line 585 of file nav.c.
References dev, nav_goto_block(), and SEND_NAVIGATION.
void nav_parse_MOVE_WP | ( | struct link_device * | dev, |
struct transport_tx * | trans, | ||
uint8_t * | buf | ||
) |
void nav_periodic_task | ( | void | ) |
Navigation main: call to the code generated from the XML flight plan.
Definition at line 445 of file nav.c.
References circle_bank, compute_dist2_to_home(), dist2_to_wp, h_ctl_course_pre_bank, nav_in_circle, nav_set_altitude(), nav_survey_active, V_CTL_AUTO_THROTTLE_STANDARD, v_ctl_auto_throttle_submode, v_ctl_mode, and V_CTL_MODE_AUTO_CLIMB.
Referenced by autopilot_static_periodic(), and navigation_task().
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 382 of file nav.c.
References CARROT, fly_to_xy(), horizontal_mode, HORIZONTAL_MODE_ROUTE, nav_carrot_leg_progress, nav_in_circle, nav_in_segment, nav_leg_length, nav_leg_progress, nav_segment_x_1, nav_segment_x_2, nav_segment_y_1, nav_segment_y_2, nav_shift, 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_land_run(), nav_launcher_run(), nav_line_osam_run(), nav_oval(), nav_points(), nav_skid_landing_run(), nav_spiral_run(), nav_survey_poly_osam_run(), nav_survey_rectangle(), nav_survey_zamboni_run(), and snav_route().
|
static |
Definition at line 413 of file nav.c.
References flight_altitude, nav_altitude, and v_ctl_altitude_setpoint.
Referenced by nav_home(), and nav_periodic_task().
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 569 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().
|
static |
Definition at line 504 of file nav.c.
References dev, nav_circle_radius, nav_circle_x, nav_circle_y, and nav_in_circle.
Referenced by nav_init(), and send_nav_status().
|
static |
Definition at line 477 of file nav.c.
References dev, and SEND_NAVIGATION.
Referenced by nav_init().
|
static |
Periodic telemetry.
Definition at line 471 of file nav.c.
References dev, ground_alt, nav_utm_east0, nav_utm_north0, and nav_utm_zone0.
Referenced by nav_init().
|
static |
Definition at line 512 of file nav.c.
References dev, nav_in_segment, nav_segment_x_1, nav_segment_x_2, nav_segment_y_1, and nav_segment_y_2.
Referenced by nav_init(), and send_nav_status().
|
static |
Definition at line 520 of file nav.c.
References dev, nav_survey_active, nav_survey_east, nav_survey_north, nav_survey_south, and nav_survey_west.
Referenced by nav_init().
|
static |
Definition at line 489 of file nav.c.
References dev, DownlinkSendWp(), and nb_waypoint.
Referenced by nav_init().
float baseleg_out_qdr |
Definition at line 219 of file nav.c.
Referenced by nav_compute_baseleg(), and nav_land_run().
float circle_bank = 0 |
Definition at line 71 of file nav.c.
Referenced by nav_circle_XY(), and nav_periodic_task().
float desired_x |
Definition at line 308 of file nav.c.
Referenced by cam_segment_periodic(), fly_to_xy(), formation_flight(), gvf_parametric_control_2D(), potential_task(), and send_desired().
float desired_y |
Definition at line 308 of file nav.c.
Referenced by cam_segment_periodic(), fly_to_xy(), formation_flight(), gvf_parametric_control_2D(), potential_task(), and send_desired().
|
static |
float flight_altitude |
Dynamically adjustable, reset to nav_altitude when it is changing.
Definition at line 74 of file nav.c.
Referenced by formation_flight(), and nav_set_altitude().
float fp_climb |
Definition at line 313 of file nav.c.
Referenced by nav_init().
float fp_pitch |
Definition at line 311 of file nav.c.
Referenced by nav_init().
float fp_throttle |
Definition at line 312 of file nav.c.
Referenced by nav_init().
uint8_t horizontal_mode |
Definition at line 70 of file nav.c.
Referenced by nav_circle_XY(), nav_route_xy(), and send_mode().
float last_x |
Definition at line 47 of file nav.c.
Referenced by gvf_nav_survey_polygon_run(), nav_init_stage(), and nav_survey_polygon_run().
float last_y |
Definition at line 47 of file nav.c.
Referenced by gvf_nav_survey_polygon_run(), nav_init_stage(), and nav_survey_polygon_run().
float nav_altitude = GROUND_ALT + MIN_HEIGHT_CARROT |
Definition at line 307 of file nav.c.
Referenced by formation_flight(), nav_home(), nav_set_altitude(), nav_skid_landing_glide(), start_formation(), stop_formation(), and tcas_periodic_task_4Hz().
|
static |
Definition at line 61 of file nav.c.
Referenced by nav_route_xy().
float nav_circle_radians |
Status on the current circle.
Definition at line 53 of file nav.c.
Referenced by nav_circle_XY(), and nav_init_stage().
float nav_circle_radians_no_rewind |
Definition at line 54 of file nav.c.
Referenced by nav_circle_XY(), and nav_init_stage().
float nav_circle_radius |
Definition at line 68 of file nav.c.
Referenced by flight_benchmark_periodic(), nav_circle_XY(), and send_circle().
float nav_circle_trigo_qdr |
Definition at line 55 of file nav.c.
Referenced by nav_circle_XY(), and nav_land_run().
float nav_circle_x |
Definition at line 68 of file nav.c.
Referenced by flight_benchmark_periodic(), nav_circle_XY(), and send_circle().
float nav_circle_y |
Definition at line 68 of file nav.c.
Referenced by flight_benchmark_periodic(), nav_circle_XY(), and send_circle().
float nav_glide_pitch_trim |
Definition at line 76 of file nav.c.
Referenced by nav_init().
float nav_ground_speed_pgain |
Definition at line 83 of file nav.c.
Referenced by nav_init().
float nav_ground_speed_setpoint |
Definition at line 83 of file nav.c.
Referenced by nav_init().
bool nav_in_circle = false |
Definition at line 66 of file nav.c.
Referenced by calculate_wind_no_airspeed(), nav_circle_XY(), nav_init_stage(), nav_periodic_task(), nav_route_xy(), nav_survey_rectangle(), and send_circle().
bool nav_in_segment = false |
Definition at line 67 of file nav.c.
Referenced by nav_circle_XY(), nav_init_stage(), nav_route_xy(), nav_survey_rectangle(), and send_segment().
|
static |
length of the current leg (m)
Definition at line 64 of file nav.c.
Referenced by nav_glide_alt(), and nav_route_xy().
|
static |
Status on the current leg (percentage, 0.
< < 1.) in route mode
Definition at line 60 of file nav.c.
Referenced by nav_glide_alt(), and nav_route_xy().
int nav_mode |
Definition at line 90 of file nav.c.
Referenced by fly_to_xy(), nav_circle_XY(), and nav_init().
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 754 of file nav.c.
Referenced by nav_oval(), and nav_oval_init().
float nav_pitch |
Definition at line 310 of file nav.c.
Referenced by attitude_loop(), nav_home(), nav_without_gps(), v_ctl_climb_auto_throttle_loop(), v_ctl_climb_loop(), v_ctl_guidance_loop(), v_ctl_landing_loop(), and v_ctl_set_pitch().
float nav_radius |
Definition at line 56 of file nav.c.
Referenced by nav_compute_baseleg(), nav_flower_run(), nav_init(), and parachute_compute_approach().
float nav_segment_x_1 |
Definition at line 69 of file nav.c.
Referenced by flight_benchmark_periodic(), nav_route_xy(), and send_segment().
float nav_segment_x_2 |
Definition at line 69 of file nav.c.
Referenced by flight_benchmark_periodic(), nav_route_xy(), and send_segment().
float nav_segment_y_1 |
Definition at line 69 of file nav.c.
Referenced by flight_benchmark_periodic(), nav_route_xy(), and send_segment().
float nav_segment_y_2 |
Definition at line 69 of file nav.c.
Referenced by flight_benchmark_periodic(), nav_route_xy(), and send_segment().
float nav_shift |
Definition at line 56 of file nav.c.
Referenced by nav_circle_XY(), nav_init_stage(), and nav_route_xy().
bool nav_survey_active |
Definition at line 88 of file nav.c.
Referenced by nav_periodic_task(), nav_survey_rectangle(), and send_survey().
float nav_survey_east |
Definition at line 87 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), and send_survey().
float nav_survey_north |
Definition at line 87 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), and send_survey().
float nav_survey_shift |
Definition at line 86 of file nav.c.
Referenced by nav_init(), nav_survey_disc_setup(), nav_survey_poly_osam_run(), nav_survey_poly_run(), nav_survey_rectangle(), and nav_survey_rectangle_init().
float nav_survey_south |
Definition at line 87 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), and send_survey().
float nav_survey_west |
Definition at line 87 of file nav.c.
Referenced by nav_survey_rectangle(), nav_survey_rectangle_init(), and send_survey().
pprz_t nav_throttle_setpoint |
Definition at line 309 of file nav.c.
Referenced by attitude_loop(), nav_without_gps(), and v_ctl_guidance_loop().
enum oval_status oval_status |