14 #define WPNAV_ACCELERATION              100.0f      // defines the default velocity vs distant curve.  maximum acceleration in cm/s/s that position controller asks for from acceleration controller    15 #define WPNAV_ACCELERATION_MIN           50.0f      // minimum acceleration in cm/s/s - used for sanity checking _wp_accel parameter    17 #define WPNAV_WP_SPEED                  500.0f      // default horizontal speed between waypoints in cm/s    18 #define WPNAV_WP_SPEED_MIN               20.0f      // minimum horizontal speed between waypoints in cm/s    19 #define WPNAV_WP_TRACK_SPEED_MIN         50.0f      // minimum speed along track of the target point the vehicle is chasing in cm/s (used as target slows down before reaching destination)    20 #define WPNAV_WP_RADIUS                 200.0f      // default waypoint radius in cm    21 #define WPNAV_WP_RADIUS_MIN              10.0f      // minimum waypoint radius in cm    23 #define WPNAV_WP_SPEED_UP               250.0f      // default maximum climb velocity    24 #define WPNAV_WP_SPEED_DOWN             150.0f      // default maximum descent velocity    26 #define WPNAV_WP_ACCEL_Z_DEFAULT        100.0f      // default vertical acceleration between waypoints in cm/s/s    28 #define WPNAV_LEASH_LENGTH_MIN          100.0f      // minimum leash lengths in cm    30 #define WPNAV_WP_FAST_OVERSHOOT_MAX     200.0f      // 2m overshoot is allowed during fast waypoints to allow for smooth transitions to next waypoint    32 #define WPNAV_YAW_DIST_MIN                 200      // minimum track length which will lead to target yaw being updated to point at next waypoint.  Under this distance the yaw target will be frozen at the current heading    33 #define WPNAV_YAW_LEASH_PCT_MIN         0.134f      // target point must be at least this distance from the vehicle (expressed as a percentage of the maximum distance it can be from the vehicle - i.e. the leash length)    35 #define WPNAV_RANGEFINDER_FILT_Z         0.25f      // range finder distance filtered at 0.25hz    67     void update_brake(
float ekfGndSpdLimit, 
float ekfNavVelGainScaler);
 
float _track_leash_length
 
void set_speed_xy(float speed_cms)
set_speed_xy - allows main code to pass target horizontal velocity for wp navigation ...
 
const AC_AttitudeControl & _attitude_control
 
void check_wp_leash_length()
 
bool _ekf_origin_terrain_alt_set
 
bool reached_wp_destination() const
reached_destination - true when we have come within RADIUS cm of the waypoint 
 
bool get_terrain_offset(float &offset_cm)
 
float get_slow_down_speed(float dist_from_dest_cm, float accel_cmss)
get_slow_down_speed - returns target speed of target point based on distance from the destination (in...
 
void calc_slow_down_distance(float speed_cms, float accel_cmss)
calc_slow_down_distance - calculates distance before waypoint that target point should begin to slow-...
 
void set_yaw_cd(float heading_cd)
 
int32_t get_pitch() const
 
Vector3f _spline_origin_vel
 
bool set_spline_destination(const Location_Class &destination, bool stopped_at_start, spline_segment_end_type seg_end_type, Location_Class next_destination)
 
AC_WPNav(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control, const AC_AttitudeControl &attitude_control)
Constructor. 
 
bool _rangefinder_available
 
void calc_spline_pos_vel(float spline_time, Vector3f &position, Vector3f &velocity)
relies on update_spline_solution being called when the segment's origin and destination were set ...
 
void get_wp_stopping_point(Vector3f &stopping_point) const
get_wp_stopping_point - returns vector to stopping point based on 3D position and velocity ...
 
bool update_spline()
update_spline - update spline controller 
 
float _limited_speed_xy_cms
 
bool advance_spline_target_along_track(float dt)
advance_spline_target_along_track - move target location along track from origin to destination ...
 
float get_accel_z() const
get_speed_z - returns target descent speed in cm/s during missions. Note: always positive ...
 
const AP_InertialNav & _inav
 
int32_t get_roll() const
get desired roll, pitch which should be fed into stabilize controllers 
 
void init_brake_target(float accel_cmss)
init_brake_target - initializes stop position from current position and velocity 
 
float get_speed_down() const
get_speed_down - returns target descent speed in cm/s during missions. Note: always positive ...
 
Vector3f _spline_destination_vel
 
void update_spline_solution(const Vector3f &origin, const Vector3f &dest, const Vector3f &origin_vel, const Vector3f &dest_vel)
spline protected functions 
 
bool set_wp_destination(const Location_Class &destination)
 
float get_speed_xy() const
get_speed_xy - allows main code to retrieve target horizontal velocity for wp navigation ...
 
int32_t get_wp_bearing_to_destination() const
get_bearing_to_destination - get bearing to next waypoint in centi-degrees 
 
void set_avoidance(AC_Avoid *avoid_ptr)
provide pointer to avoidance library 
 
float get_roll() const
get desired roll, pitch which should be fed into stabilize controllers 
 
bool set_spline_origin_and_destination(const Vector3f &origin, const Vector3f &destination, bool terrain_alt, bool stopped_at_start, spline_segment_end_type seg_end_type, const Vector3f &next_destination)
 
A system for managing and storing variables that are of general interest to the system. 
 
bool update_wpnav()
update_wpnav - run the wp controller - should be called at 100hz or higher 
 
const Vector3f & get_wp_destination() const
get_wp_destination waypoint using position vector (distance from ekf origin in cm) ...
 
ArduCopter attitude control library. 
 
static const struct AP_Param::GroupInfo var_info[]
 
const Vector3f & get_wp_origin() const
get origin using position vector (distance from ekf origin in cm) 
 
void set_fast_waypoint(bool fast)
set_fast_waypoint - set to true to ignore the waypoint radius and consider the waypoint 'reached' the...
 
float get_wp_distance_to_destination() const
get_wp_distance_to_destination - get horizontal distance to destination in cm 
 
bool set_wp_destination_NED(const Vector3f &destination_NED)
set waypoint destination using NED position vector from ekf origin in meters 
 
float get_speed_up() const
get_speed_up - returns target climb speed in cm/s during missions 
 
uint8_t reached_destination
 
bool get_vector_NEU(const Location_Class &loc, Vector3f &vec, bool &terrain_alt)
 
bool set_wp_origin_and_destination(const Vector3f &origin, const Vector3f &destination, bool terrain_alt=false)
 
AC_PosControl & _pos_control
 
void shift_wp_origin_to_current_pos()
 
void wp_and_spline_init()
 
bool _rangefinder_healthy
 
bool reached_spline_destination() const
reached_spline_destination - true when we have come within RADIUS cm of the waypoint ...
 
float get_wp_acceleration() const
get_wp_acceleration - returns acceleration in cm/s/s during missions 
 
Vector3f _hermite_spline_solution[4]
 
Common definitions and utility routines for the ArduPilot libraries. 
 
void get_wp_stopping_point_xy(Vector3f &stopping_point) const
get_wp_stopping_point_xy - returns vector to stopping point based on a horizontal position and veloci...
 
AP_Float _wp_speed_down_cms
 
AP_Float _wp_accel_z_cmss
 
void update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler)
update_brake - run the brake controller - should be called at 400hz 
 
AP_Float _wp_speed_up_cms
 
void calculate_wp_leash_length()
calculate_wp_leash_length - calculates track speed, acceleration and leash lengths for waypoint contr...
 
struct AC_WPNav::wpnav_flags _flags
 
uint8_t new_wp_destination
 
void set_terrain(AP_Terrain *terrain_ptr)
provide pointer to terrain database 
 
const AP_AHRS_View & _ahrs
 
void set_rangefinder_alt(bool use, bool healthy, float alt_cm)
provide rangefinder altitude 
 
float _rangefinder_alt_cm
 
bool advance_wp_target_along_track(float dt)
advance_wp_target_along_track - move target location along track from origin to destination ...