80 _pos_control(pos_control),
81 _attitude_control(attitude_control),
85 _track_length_xy(0.0
f),
87 _limited_speed_xy_cms(0.0
f),
90 _track_leash_length(0.0
f),
91 _slow_down_dist(0.0
f),
93 _spline_time_scale(0.0
f),
94 _spline_vel_scaler(0.0
f),
206 if (!
AP::ahrs().get_origin(destination)) {
209 destination.
offset(dest.
x*0.01f, dest.
y*0.01f);
210 destination.
alt += dest.
z;
231 float origin_terr_offset;
235 origin.
z -= origin_terr_offset;
277 float origin_terr_offset = 0.0f;
318 Vector3f pos_diff = curr_pos - pos_target;
347 float track_desired_max;
348 float track_leash_slack;
349 bool reached_leash_limit =
false;
355 float terr_offset = 0.0f;
370 track_error = curr_delta - track_covered_pos;
373 float track_error_xy =
norm(track_error.
x, track_error.
y);
376 float track_error_z = fabsf(track_error.
z);
388 track_desired_max = track_covered + track_leash_slack;
392 reached_leash_limit =
true;
408 if (speed_along_track < -linear_velocity) {
413 if(dt > 0 && !reached_leash_limit) {
432 if (fabsf(speed_along_track) < linear_velocity) {
437 if (!reached_leash_limit) {
460 final_target.
z += terr_offset;
485 Vector3f horiz_leash_xy = final_target - curr_pos;
486 horiz_leash_xy.
z = 0;
583 }
else if(
is_zero(pos_delta_unit_xy)){
643 bool next_dest_terr_alt;
644 if (!
get_vector_NEU(next_destination, next_dest_neu, next_dest_terr_alt)) {
677 origin.
z -= terr_offset;
709 if (stopped_at_start || !prev_segment_exists) {
738 switch (seg_end_type) {
761 float pos_len = (destination - origin).length() * 4.0f;
762 if (vel_len > pos_len) {
765 float vel_scaling = pos_len / vel_len;
782 float terr_offset = 0.0f;
859 float target_vel_length = target_vel.
length();
860 if (
is_zero(target_vel_length)) {
872 float terr_offset = 0.0f;
878 Vector3f track_error = curr_pos - target_pos;
879 track_error.
z -= terr_offset;
882 float track_error_xy =
norm(track_error.
x, track_error.
y);
885 float track_error_z = fabsf(track_error.
z);
890 if (track_error.
z >= 0) {
898 if (track_leash_slack < 0.0
f) {
899 track_leash_slack = 0.0f;
903 float spline_dist_to_wp = (
_destination - target_pos).length();
906 vel_limit =
MIN(vel_limit, track_leash_slack/dt);
924 target_pos.z += terr_offset;
936 float track_error_xy_length =
safe_sqrt(
sq(track_error.
x)+
sq(track_error.
y));
960 float spline_time_sqrd = spline_time * spline_time;
961 float spline_time_cubed = spline_time_sqrd * spline_time;
964 _hermite_spline_solution[1] * spline_time + \
965 _hermite_spline_solution[2] * spline_time_sqrd + \
966 _hermite_spline_solution[3] * spline_time_cubed;
969 _hermite_spline_solution[2] * 2.0f * spline_time + \
970 _hermite_spline_solution[3] * 3.0f * spline_time_sqrd;
976 #if AP_TERRAIN_AVAILABLE 988 float terr_alt = 0.0f;
989 if (
_terrain !=
nullptr &&
_terrain->height_above_terrain(terr_alt,
true)) {
1016 terrain_alt =
false;
1022 terrain_alt =
false;
1040 if (accel_cmss <= 0.0
f) {
1053 if (dist_from_dest_cm <= 0) {
1058 float target_speed =
safe_sqrt(dist_from_dest_cm * 4.0
f * accel_cmss);
1064 return target_speed;
float _track_leash_length
float norm(const T first, const U second, const Params... parameters)
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 get_stopping_point_xy(Vector3f &stopping_point) const
void check_wp_leash_length()
#define WPNAV_WP_TRACK_SPEED_MIN
void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms)
bool get_terrain_offset(float &offset_cm)
Vector3< float > Vector3f
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)
virtual const Vector3f & get_position() const =0
float safe_sqrt(const T v)
const Vector3f & get_vel_target() const
accessors for reporting
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)
void get_stopping_point_z(Vector3f &stopping_point) const
get_stopping_point_z - calculates stopping point based on current position, velocity, vehicle acceleration
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 clear_desired_velocity_ff_z()
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 ...
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
#define WPNAV_WP_SPEED_MIN
bool update_spline()
update_spline - update spline controller
#define AP_GROUPINFO(name, idx, clazz, element, def)
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_leash_up_z() const
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
#define WPNAV_WP_ACCEL_Z_DEFAULT
const AP_InertialNav & _inav
#define WPNAV_YAW_DIST_MIN
#define WPNAV_LEASH_LENGTH_MIN
void init_brake_target(float accel_cmss)
init_brake_target - initializes stop position from current position and velocity
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)
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
int32_t get_wp_bearing_to_destination() const
get_bearing_to_destination - get bearing to next waypoint in centi-degrees
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
void set_xy_target(float x, float y)
set_xy_target in cm from home
#define RadiansToCentiDegrees(x)
#define WPNAV_WP_FAST_OVERSHOOT_MAX
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)
bool update_wpnav()
update_wpnav - run the wp controller - should be called at 100hz or higher
float lean_angle_max() const
const Vector3f & get_wp_destination() const
get_wp_destination waypoint using position vector (distance from ekf origin in cm) ...
const Vector3f & get_pos_target() const
get_pos_target - get target as position vector (from home in cm)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
ALT_FRAME get_alt_frame() const
static const struct AP_Param::GroupInfo var_info[]
bool is_zero(const T fVal1)
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
get altitude in desired frame
void init_xy_controller(bool reset_I=true)
float get_leash_down_z() const
void set_speed_z(float speed_down, float speed_up)
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
void calc_leash_length_z()
uint8_t reached_destination
void offset(float ofs_north, float ofs_east)
#define WPNAV_WP_SPEED_UP
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()
void calc_leash_length_xy()
bool _rangefinder_healthy
void set_accel_z(float accel_cmss)
set_accel_z - set vertical acceleration in cm/s/s
bool change_alt_frame(ALT_FRAME desired_frame)
void set_pos_target(const Vector3f &position)
set_pos_target in cm from home
Vector3f _hermite_spline_solution[4]
void freeze_ff_z()
freeze_ff_z - used to stop the feed forward being calculated during a known discontinuity ...
#define WPNAV_WP_RADIUS_MIN
float constrain_float(const float amt, const float low, const float high)
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...
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
AP_Float _wp_speed_down_cms
void set_accel_xy(float accel_cmss)
set_accel_xy - set horizontal acceleration in cm/s/s
Vector3f get_att_target_euler_cd() const
#define WPNAV_YAW_LEASH_PCT_MIN
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...
#define WPNAV_ACCELERATION
float time_since_last_xy_update() const
virtual const Vector3f & get_velocity() const =0
struct AC_WPNav::wpnav_flags _flags
float get_leash_xy() const
#define WPNAV_WP_SPEED_DOWN
uint8_t new_wp_destination
virtual float get_altitude() const =0
void set_speed_xy(float speed_cms)
set_speed_xy - set horizontal speed maximum in cm/s
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 ...
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)