ardupilot/libraries/AC_WPNav/AC_WPNav.cpp

538 lines
20 KiB
C++
Raw Normal View History

2013-03-20 03:27:26 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include <AC_WPNav.h>
extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
// index 0 was used for the old orientation matrix
// @Param: SPEED
// @DisplayName: Waypoint Horizontal Speed Target
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission
// @Units: cm/s
// @Range: 0 2000
// @Increment: 50
// @User: Standard
AP_GROUPINFO("SPEED", 0, AC_WPNav, _wp_speed_cms, WPNAV_WP_SPEED),
// @Param: RADIUS
// @DisplayName: Waypoint Radius
// @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit.
// @Units: cm
// @Range: 100 1000
// @Increment: 1
// @User: Standard
AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS),
2013-03-20 03:27:26 -03:00
// @Param: SPEED_UP
// @DisplayName: Waypoint Climb Speed Target
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
// @Units: cm/s
// @Range: 0 1000
// @Increment: 50
// @User: Standard
AP_GROUPINFO("SPEED_UP", 2, AC_WPNav, _wp_speed_up_cms, WPNAV_WP_SPEED_UP),
// @Param: SPEED_DN
// @DisplayName: Waypoint Descent Speed Target
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
// @Units: cm/s
// @Range: 0 1000
// @Increment: 50
// @User: Standard
AP_GROUPINFO("SPEED_DN", 3, AC_WPNav, _wp_speed_down_cms, WPNAV_WP_SPEED_DOWN),
// @Param: LOIT_SPEED
// @DisplayName: Loiter Horizontal Maximum Speed
// @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode
// @Units: cm/s
// @Range: 0 2000
// @Increment: 50
// @User: Standard
AP_GROUPINFO("LOIT_SPEED", 4, AC_WPNav, _loiter_speed_cms, WPNAV_LOITER_SPEED),
// @Param: ACCEL
// @DisplayName: Waypoint Acceleration
// @Description: Defines the horizontal acceleration in cm/s/s used during missions
// @Units: cm/s/s
// @Range: 0 980
// @Increment: 10
// @User: Standard
AP_GROUPINFO("ACCEL", 5, AC_WPNav, _wp_accel_cms, WPNAV_ACCELERATION),
2013-03-20 03:27:26 -03:00
AP_GROUPEND
};
// Default constructor.
// Note that the Vector/Matrix constructors already implicitly zero
// their values.
//
2014-01-19 06:26:29 -04:00
AC_WPNav::AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, AC_PosControl& pos_control,
APM_PI* pid_pos_lat, APM_PI* pid_pos_lon, AC_PID* pid_rate_lat, AC_PID* pid_rate_lon) :
2013-03-20 03:27:26 -03:00
_inav(inav),
_ahrs(ahrs),
_pos_control(pos_control),
2013-03-20 03:27:26 -03:00
_pid_pos_lat(pid_pos_lat),
_pid_pos_lon(pid_pos_lon),
2013-03-21 06:28:10 -03:00
_pid_rate_lat(pid_rate_lat),
_pid_rate_lon(pid_rate_lon),
_loiter_last_update(0),
2014-01-19 06:26:29 -04:00
_loiter_step(0),
_pilot_accel_fwd_cms(0),
_pilot_accel_rgt_cms(0),
2013-05-14 23:51:26 -03:00
_loiter_leash(WPNAV_MIN_LEASH_LENGTH),
_loiter_accel_cms(WPNAV_LOITER_ACCEL_MAX),
2014-01-19 06:26:29 -04:00
_wp_last_update(0),
_wp_step(0),
_track_length(0.0),
_track_desired(0.0),
2013-05-14 23:51:26 -03:00
_wp_leash_xy(WPNAV_MIN_LEASH_LENGTH),
_wp_leash_z(WPNAV_MIN_LEASH_LENGTH),
2014-01-19 06:26:29 -04:00
_track_accel(0.0),
_track_speed(0.0),
_track_leash_length(0.0)
2013-03-20 03:27:26 -03:00
{
AP_Param::setup_object_defaults(this, var_info);
// initialise leash lengths
calculate_wp_leash_length(true);
calculate_loiter_leash_length();
2013-03-20 03:27:26 -03:00
}
///
2014-01-19 06:26:29 -04:00
/// loiter controller
2013-03-20 03:27:26 -03:00
///
2014-01-19 06:26:29 -04:00
/// set_loiter_target in cm from home
void AC_WPNav::set_loiter_target(const Vector3f& position)
{
2014-01-19 06:26:29 -04:00
// set target position
_pos_control.set_pos_target(_inav->get_position());
// initialise feed forward velocity to zero
_pos_control.set_desired_velocity(0,0);
// initialise pos controller speed, acceleration and leash length
_pos_control.set_speed_xy(_loiter_speed_cms);
_pos_control.set_accel_xy(_loiter_accel_cms);
_pos_control.set_leash_xy(_loiter_leash);
// initialise pilot input
2014-01-19 06:26:29 -04:00
_pilot_accel_fwd_cms = 0;
_pilot_accel_rgt_cms = 0;
}
2014-01-19 06:26:29 -04:00
/// init_loiter_target - initialize's loiter position and feed-forward velocity from current pos and velocity
void AC_WPNav::init_loiter_target()
{
2014-01-19 06:26:29 -04:00
Vector3f curr_vel = _inav->get_velocity();
2014-01-19 06:26:29 -04:00
// set target position
_pos_control.set_pos_target(_inav->get_position());
2013-05-14 23:51:26 -03:00
2014-01-19 06:26:29 -04:00
// initialise feed forward velocities to zero
_pos_control.set_desired_velocity(curr_vel.x, curr_vel.y);
2014-01-19 06:26:29 -04:00
// initialise pos controller speed, acceleration and leash length
// To-Do: will this cause problems for circle which calls this continuously?
_pos_control.set_speed_xy(_loiter_speed_cms);
_pos_control.set_accel_xy(_loiter_accel_cms);
_pos_control.set_leash_xy(_loiter_leash);
2014-01-19 06:26:29 -04:00
// initialise pilot input
_pilot_accel_fwd_cms = 0;
_pilot_accel_rgt_cms = 0;
}
2014-01-19 06:26:29 -04:00
/// calculate_loiter_leash_length - calculates the maximum distance in cm that the target position may be from the current location
void AC_WPNav::calculate_loiter_leash_length()
{
2014-01-19 06:26:29 -04:00
_loiter_leash = _pos_control.calc_leash_length_xy(_loiter_speed_cms,_loiter_accel_cms);
}
2014-01-19 06:26:29 -04:00
/// set_pilot_desired_acceleration - sets pilot desired acceleration from roll and pitch stick input
void AC_WPNav::set_pilot_desired_acceleration(float control_roll, float control_pitch)
{
2014-01-19 06:26:29 -04:00
// convert pilot input to desired acceleration in cm/s/s
_pilot_accel_fwd_cms = -control_pitch * _loiter_accel_cms / 4500.0f;
_pilot_accel_rgt_cms = control_roll * _loiter_accel_cms / 4500.0f;
}
2014-01-19 06:26:29 -04:00
/// get_loiter_stopping_point_xy - returns vector to stopping point based on a horizontal position and velocity
void AC_WPNav::get_loiter_stopping_point_xy(Vector3f& stopping_point) const
2013-03-20 03:27:26 -03:00
{
2014-01-19 06:26:29 -04:00
_pos_control.get_stopping_point_xy(stopping_point);
}
2014-01-19 06:26:29 -04:00
/// calc_loiter_desired_velocity - updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance
/// updated velocity sent directly to position controller
void AC_WPNav::calc_loiter_desired_velocity(float nav_dt)
{
// range check nav_dt
if( nav_dt < 0 ) {
return;
}
2013-05-24 11:45:03 -03:00
// check loiter speed and avoid divide by zero
if( _loiter_speed_cms < 100.0f) {
_loiter_speed_cms = 100.0f;
}
2013-03-20 03:27:26 -03:00
2013-05-24 11:45:03 -03:00
// rotate pilot input to lat/lon frame
2014-01-19 06:26:29 -04:00
Vector2f desired_accel;
desired_accel.x = (_pilot_accel_fwd_cms*_ahrs->cos_yaw() - _pilot_accel_rgt_cms*_ahrs->sin_yaw());
desired_accel.y = (_pilot_accel_fwd_cms*_ahrs->sin_yaw() + _pilot_accel_rgt_cms*_ahrs->cos_yaw());
// get pos_control's feed forward velocity
Vector2f desired_vel = _pos_control.get_desired_velocity();
// add pilot commanded acceleration
desired_vel += desired_accel * nav_dt;
// reduce velocity with fake wind resistance
if(desired_vel.x > 0 ) {
desired_vel.x -= (_loiter_accel_cms-WPNAV_LOITER_ACCEL_MIN)*nav_dt*desired_vel.x/_loiter_speed_cms;
desired_vel.x = max(desired_vel.x - WPNAV_LOITER_ACCEL_MIN*nav_dt, 0);
}else if(desired_vel.x < 0) {
desired_vel.x -= (_loiter_accel_cms-WPNAV_LOITER_ACCEL_MIN)*nav_dt*desired_vel.x/_loiter_speed_cms;
desired_vel.x = min(desired_vel.x + WPNAV_LOITER_ACCEL_MIN*nav_dt, 0);
}
if(desired_vel.y > 0 ) {
desired_vel.y -= (_loiter_accel_cms-WPNAV_LOITER_ACCEL_MIN)*nav_dt*desired_vel.y/_loiter_speed_cms;
desired_vel.y = max(desired_vel.y - WPNAV_LOITER_ACCEL_MIN*nav_dt, 0);
}else if(desired_vel.y < 0) {
desired_vel.y -= (_loiter_accel_cms-WPNAV_LOITER_ACCEL_MIN)*nav_dt*desired_vel.y/_loiter_speed_cms;
desired_vel.y = min(desired_vel.y + WPNAV_LOITER_ACCEL_MIN*nav_dt, 0);
}
// constrain and scale the feed forward velocity if necessary
float vel_total = safe_sqrt(desired_vel.x*desired_vel.x + desired_vel.y*desired_vel.y);
2013-05-14 23:51:26 -03:00
if (vel_total > _loiter_speed_cms && vel_total > 0.0f) {
2014-01-19 06:26:29 -04:00
desired_vel.x = _loiter_speed_cms * desired_vel.x/vel_total;
desired_vel.y = _loiter_speed_cms * desired_vel.y/vel_total;
2013-03-20 03:27:26 -03:00
}
2014-01-19 06:26:29 -04:00
// send adjusted feed forward velocity back to position controller
_pos_control.set_desired_velocity(desired_vel.x,desired_vel.y);
2013-03-20 03:27:26 -03:00
}
/// get_bearing_to_target - get bearing to loiter target in centi-degrees
2014-01-19 06:26:29 -04:00
int32_t AC_WPNav::get_loiter_bearing_to_target() const
{
2014-01-19 06:26:29 -04:00
return get_bearing_cd(_inav->get_position(), _pos_control.get_pos_target());
}
2014-01-19 06:26:29 -04:00
/// update_loiter - run the loiter controller - should be called at 100hz
void AC_WPNav::update_loiter()
{
// calculate dt
uint32_t now = hal.scheduler->millis();
float dt = (now - _loiter_last_update) / 1000.0f;
// reset step back to 0 if 0.1 seconds has passed and we completed the last full cycle
2014-01-19 06:26:29 -04:00
if (dt > 0.095f) {
// double check dt is reasonable
if (dt >= 1.0f) {
dt = 0.0;
}
// capture time since last iteration
_loiter_last_update = now;
// translate any adjustments from pilot to loiter target
2014-01-19 06:26:29 -04:00
calc_loiter_desired_velocity(dt);
// trigger position controller on next update
_pos_control.trigger_xy();
}else{
// run loiter's position to velocity step
2014-01-19 06:26:29 -04:00
_pos_control.update_pos_controller(true);
}
}
2013-03-20 03:27:26 -03:00
///
/// waypoint navigation
///
/// set_destination - set destination using cm from home
2014-01-19 06:26:29 -04:00
void AC_WPNav::set_wp_destination(const Vector3f& destination)
2013-03-20 03:27:26 -03:00
{
2014-01-19 06:26:29 -04:00
// if waypoint controller is active and copter has reached the previous waypoint use it for the origin
if( _flags.reached_destination && ((hal.scheduler->millis() - _wp_last_update) < 1000) ) {
_origin = _destination;
}else{
// otherwise calculate origin from the current position and velocity
2014-01-19 06:26:29 -04:00
_pos_control.get_stopping_point_xy(_origin);
}
// set origin and destination
2014-01-19 06:26:29 -04:00
set_wp_origin_and_destination(_origin, destination);
2013-03-20 03:27:26 -03:00
}
/// set_origin_and_destination - set origin and destination using lat/lon coordinates
2014-01-19 06:26:29 -04:00
void AC_WPNav::set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination)
2013-03-20 03:27:26 -03:00
{
// store origin and destination locations
2013-03-20 03:27:26 -03:00
_origin = origin;
_destination = destination;
Vector3f pos_delta = _destination - _origin;
_track_length = pos_delta.length(); // get track length
2013-05-14 23:51:26 -03:00
// calculate each axis' percentage of the total distance to the destination
if (_track_length == 0.0f) {
// avoid possible divide by zero
_pos_delta_unit.x = 0;
_pos_delta_unit.y = 0;
_pos_delta_unit.z = 0;
2013-05-24 11:45:03 -03:00
}else{
2013-05-14 23:51:26 -03:00
_pos_delta_unit = pos_delta/_track_length;
}
2014-01-19 06:26:29 -04:00
// calculate leash lengths
bool climb = pos_delta.z >= 0; // climbing vs descending leads to different leash lengths because speed_up_cms and speed_down_cms can be different
calculate_wp_leash_length(climb);
// initialise intermediate point to the origin
2014-01-19 06:26:29 -04:00
_pos_control.set_pos_target(origin);
_track_desired = 0; // target is at beginning of track
_flags.reached_destination = false;
2014-01-19 06:26:29 -04:00
_flags.fast_waypoint = false; // default waypoint back to slow
// initialise the limited speed to current speed along the track
const Vector3f &curr_vel = _inav->get_velocity();
// get speed along track (note: we convert vertical speed into horizontal speed equivalent)
float speed_along_track = curr_vel.x * _pos_delta_unit.x + curr_vel.y * _pos_delta_unit.y + curr_vel.z * _pos_delta_unit.z;
_limited_speed_xy_cms = constrain_float(speed_along_track,0,_wp_speed_cms);
2014-01-19 06:26:29 -04:00
}
2014-01-19 06:26:29 -04:00
/// get_wp_stopping_point_xy - returns vector to stopping point based on a horizontal position and velocity
void AC_WPNav::get_wp_stopping_point_xy(Vector3f& stopping_point) const
{
_pos_control.get_stopping_point_xy(stopping_point);
2013-03-20 03:27:26 -03:00
}
2014-01-19 06:26:29 -04:00
/// advance_wp_target_along_track - move target location along track from origin to destination
void AC_WPNav::advance_wp_target_along_track(float dt)
2013-03-20 03:27:26 -03:00
{
float track_covered;
Vector3f track_error;
2013-03-20 03:27:26 -03:00
float track_desired_max;
float track_desired_temp = _track_desired;
float track_extra_max;
2013-03-20 03:27:26 -03:00
// get current location
Vector3f curr_pos = _inav->get_position();
Vector3f curr_delta = curr_pos - _origin;
2013-03-20 03:27:26 -03:00
// calculate how far along the track we are
track_covered = curr_delta.x * _pos_delta_unit.x + curr_delta.y * _pos_delta_unit.y + curr_delta.z * _pos_delta_unit.z;
Vector3f track_covered_pos = _pos_delta_unit * track_covered;
track_error = curr_delta - track_covered_pos;
// calculate the horizontal error
float track_error_xy = safe_sqrt(track_error.x*track_error.x + track_error.y*track_error.y);
// calculate the vertical error
float track_error_z = fabsf(track_error.z);
// calculate how far along the track we could move the intermediate target before reaching the end of the leash
track_extra_max = min(_track_leash_length*(_wp_leash_z-track_error_z)/_wp_leash_z, _track_leash_length*(_wp_leash_xy-track_error_xy)/_wp_leash_xy);
if(track_extra_max <0) {
track_desired_max = track_covered;
}else{
track_desired_max = track_covered + track_extra_max;
}
// get current velocity
const Vector3f &curr_vel = _inav->get_velocity();
// get speed along track
float speed_along_track = curr_vel.x * _pos_delta_unit.x + curr_vel.y * _pos_delta_unit.y + curr_vel.z * _pos_delta_unit.z;
// calculate point at which velocity switches from linear to sqrt
float linear_velocity = _wp_speed_cms;
float kP = _pid_pos_lat->kP();
if (kP >= 0.0f) { // avoid divide by zero
linear_velocity = _track_accel/kP;
}
// let the limited_speed_xy_cms be some range above or below current velocity along track
if (speed_along_track < -linear_velocity) {
// we are travelling fast in the opposite direction of travel to the waypoint so do not move the intermediate point
_limited_speed_xy_cms = 0;
}else{
// increase intermediate target point's velocity if not yet at target speed (we will limit it below)
if(dt > 0) {
if(track_desired_max > _track_desired) {
2013-12-10 19:21:41 -04:00
_limited_speed_xy_cms += 2.0f * _track_accel * dt;
}else{
// do nothing, velocity stays constant
_track_desired = track_desired_max;
}
}
// do not go over top speed
if(_limited_speed_xy_cms > _track_speed) {
_limited_speed_xy_cms = _track_speed;
}
// if our current velocity is within the linear velocity range limit the intermediate point's velocity to be no more than the linear_velocity above or below our current velocity
if (fabsf(speed_along_track) < linear_velocity) {
_limited_speed_xy_cms = constrain_float(_limited_speed_xy_cms,speed_along_track-linear_velocity,speed_along_track+linear_velocity);
}
}
2013-03-20 03:27:26 -03:00
// advance the current target
track_desired_temp += _limited_speed_xy_cms * dt;
2013-04-05 06:55:23 -03:00
// do not let desired point go past the end of the segment
track_desired_temp = constrain_float(track_desired_temp, 0, _track_length);
_track_desired = max(_track_desired, track_desired_temp);
2013-03-20 03:27:26 -03:00
// recalculate the desired position
2014-01-19 06:26:29 -04:00
_pos_control.set_pos_target(_origin + _pos_delta_unit * _track_desired);
// check if we've reached the waypoint
if( !_flags.reached_destination ) {
if( _track_desired >= _track_length ) {
// "fast" waypoints are complete once the intermediate point reaches the destination
if (_flags.fast_waypoint) {
_flags.reached_destination = true;
}else{
// regular waypoints also require the copter to be within the waypoint radius
Vector3f dist_to_dest = curr_pos - _destination;
if( dist_to_dest.length() <= _wp_radius_cm ) {
_flags.reached_destination = true;
}
}
}
}
2013-03-20 03:27:26 -03:00
}
2014-01-19 06:26:29 -04:00
/// get_wp_distance_to_destination - get horizontal distance to destination in cm
float AC_WPNav::get_wp_distance_to_destination()
2013-03-20 03:27:26 -03:00
{
// get current location
Vector3f curr = _inav->get_position();
return pythagorous2(_destination.x-curr.x,_destination.y-curr.y);
}
2013-03-20 03:27:26 -03:00
2014-01-19 06:26:29 -04:00
/// get_wp_bearing_to_destination - get bearing to next waypoint in centi-degrees
int32_t AC_WPNav::get_wp_bearing_to_destination()
{
return get_bearing_cd(_inav->get_position(), _destination);
}
2013-03-20 03:27:26 -03:00
/// update_wpnav - run the wp controller - should be called at 10hz
void AC_WPNav::update_wpnav()
{
// calculate dt
uint32_t now = hal.scheduler->millis();
2014-01-19 06:26:29 -04:00
float dt = (now - _wp_last_update) / 1000.0f;
// reset step back to 0 if 0.1 seconds has passed and we completed the last full cycle
2014-01-19 06:26:29 -04:00
if (dt > 0.095f) {
// double check dt is reasonable
if (dt >= 1.0f) {
dt = 0.0;
}
// capture time since last iteration
2014-01-19 06:26:29 -04:00
_wp_last_update = now;
// advance the target if necessary
2014-01-19 06:26:29 -04:00
advance_wp_target_along_track(dt);
_pos_control.trigger_xy();
}else{
// run position controller
_pos_control.update_pos_controller(false);
}
2013-03-20 03:27:26 -03:00
}
///
/// shared methods
///
// get_bearing_cd - return bearing in centi-degrees between two positions
// To-Do: move this to math library
float AC_WPNav::get_bearing_cd(const Vector3f &origin, const Vector3f &destination) const
{
float bearing = 9000 + atan2f(-(destination.x-origin.x), destination.y-origin.y) * 5729.57795f;
if (bearing < 0) {
bearing += 36000;
}
return bearing;
}
/// calculate_wp_leash_length - calculates horizontal and vertical leash lengths for waypoint controller
void AC_WPNav::calculate_wp_leash_length(bool climb)
{
// get loiter position P
float kP = _pid_pos_lat->kP();
2014-01-19 06:26:29 -04:00
float althold_kP = _pos_control.althold_kP();
// sanity check acceleration and avoid divide by zero
if (_wp_accel_cms <= 0.0f) {
_wp_accel_cms = WPNAV_ACCELERATION_MIN;
}
2013-05-14 23:51:26 -03:00
// avoid divide by zero
if (kP <= 0.0f) {
_wp_leash_xy = WPNAV_MIN_LEASH_LENGTH;
return;
}
2014-01-19 06:26:29 -04:00
// calculate horizontal leash length
if(_wp_speed_cms <= _wp_accel_cms / kP) {
// linear leash length based on speed close in
_wp_leash_xy = _wp_speed_cms / kP;
}else{
// leash length grows at sqrt of speed further out
_wp_leash_xy = (_wp_accel_cms / (2.0f*kP*kP)) + (_wp_speed_cms*_wp_speed_cms / (2.0f*_wp_accel_cms));
}
// ensure leash is at least 1m long
2013-05-14 23:51:26 -03:00
if( _wp_leash_xy < WPNAV_MIN_LEASH_LENGTH ) {
_wp_leash_xy = WPNAV_MIN_LEASH_LENGTH;
}
// calculate vertical leash length
float speed_vert;
if( climb ) {
speed_vert = _wp_speed_up_cms;
}else{
speed_vert = _wp_speed_down_cms;
}
2014-01-19 06:26:29 -04:00
if(speed_vert <= WPNAV_ALT_HOLD_ACCEL_MAX / althold_kP) {
// linear leash length based on speed close in
2014-01-19 06:26:29 -04:00
_wp_leash_z = speed_vert / althold_kP;
}else{
// leash length grows at sqrt of speed further out
2014-01-19 06:26:29 -04:00
_wp_leash_z = (WPNAV_ALT_HOLD_ACCEL_MAX / (2.0*althold_kP*althold_kP)) + (speed_vert*speed_vert / (2*WPNAV_ALT_HOLD_ACCEL_MAX));
}
// ensure leash is at least 1m long
if( _wp_leash_z < WPNAV_MIN_LEASH_LENGTH ) {
_wp_leash_z = WPNAV_MIN_LEASH_LENGTH;
}
// length of the unit direction vector in the horizontal
float pos_delta_unit_xy = sqrt(_pos_delta_unit.x*_pos_delta_unit.x+_pos_delta_unit.y*_pos_delta_unit.y);
float pos_delta_unit_z = fabsf(_pos_delta_unit.z);
// calculate the maximum acceleration, maximum velocity, and leash length in the direction of travel
if(pos_delta_unit_z == 0 && pos_delta_unit_xy == 0){
_track_accel = 0;
_track_speed = 0;
_track_leash_length = WPNAV_MIN_LEASH_LENGTH;
}else if(_pos_delta_unit.z == 0){
_track_accel = _wp_accel_cms/pos_delta_unit_xy;
_track_speed = _wp_speed_cms/pos_delta_unit_xy;
_track_leash_length = _wp_leash_xy/pos_delta_unit_xy;
}else if(pos_delta_unit_xy == 0){
_track_accel = WPNAV_ALT_HOLD_ACCEL_MAX/pos_delta_unit_z;
_track_speed = speed_vert/pos_delta_unit_z;
_track_leash_length = _wp_leash_z/pos_delta_unit_z;
}else{
_track_accel = min(WPNAV_ALT_HOLD_ACCEL_MAX/pos_delta_unit_z, _wp_accel_cms/pos_delta_unit_xy);
_track_speed = min(speed_vert/pos_delta_unit_z, _wp_speed_cms/pos_delta_unit_xy);
_track_leash_length = min(_wp_leash_z/pos_delta_unit_z, _wp_leash_xy/pos_delta_unit_xy);
}
}