mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_WPNav: rename some definitions
This commit is contained in:
parent
2167dd7d3e
commit
648787a6c8
@ -76,7 +76,7 @@ AC_WPNav::AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, AC_PosContro
|
||||
_loiter_step(0),
|
||||
_pilot_accel_fwd_cms(0),
|
||||
_pilot_accel_rgt_cms(0),
|
||||
_loiter_accel_cms(WPNAV_LOITER_ACCEL_MAX),
|
||||
_loiter_accel_cms(WPNAV_LOITER_ACCEL),
|
||||
_wp_last_update(0),
|
||||
_wp_step(0),
|
||||
_track_length(0.0),
|
||||
@ -509,7 +509,7 @@ void AC_WPNav::calculate_wp_leash_length()
|
||||
if(pos_delta_unit_z == 0 && pos_delta_unit_xy == 0){
|
||||
_track_accel = 0;
|
||||
_track_speed = 0;
|
||||
_track_leash_length = WPNAV_MIN_LEASH_LENGTH;
|
||||
_track_leash_length = WPNAV_LEASH_LENGTH_MIN;
|
||||
}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;
|
||||
|
@ -11,17 +11,11 @@
|
||||
// loiter maximum velocities and accelerations
|
||||
#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
|
||||
#define WPNAV_ACCELERATION_MIN 50.0f // minimum acceleration in cm/s/s - used for sanity checking _wp_accel parameter
|
||||
#define WPNAV_ACCEL_MAX 980.0f // max acceleration in cm/s/s that the loiter velocity controller will ask from the lower accel controller.
|
||||
// should be 1.5 times larger than WPNAV_ACCELERATION.
|
||||
// max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s
|
||||
|
||||
#define WPNAV_LOITER_SPEED 500.0f // maximum default loiter speed in cm/s
|
||||
#define WPNAV_LOITER_SPEED 500.0f // default loiter speed in cm/s
|
||||
#define WPNAV_LOITER_SPEED_MIN 100.0f // minimum loiter speed in cm/s
|
||||
#define WPNAV_LOITER_ACCEL_MAX 250.0f // maximum acceleration in loiter mode
|
||||
#define WPNAV_LOITER_ACCEL 250.0f // default acceleration in loiter mode
|
||||
#define WPNAV_LOITER_ACCEL_MIN 25.0f // minimum acceleration in loiter mode
|
||||
#define WPNAV_LOITER_SPEED_MAX_TO_CORRECT_ERROR 200.0f // maximum speed used to correct position error (i.e. not including feed forward)
|
||||
|
||||
#define MAX_LEAN_ANGLE 4500 // default maximum lean angle
|
||||
|
||||
#define WPNAV_WP_SPEED 500.0f // default horizontal speed betwen waypoints in cm/s
|
||||
#define WPNAV_WP_SPEED_MIN 100.0f // minimum horitzontal speed between waypoints in cm/s
|
||||
@ -30,10 +24,9 @@
|
||||
#define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity
|
||||
#define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity
|
||||
|
||||
#define WPNAV_ALT_HOLD_P 1.0f // default throttle controller's altitude hold's P gain.
|
||||
#define WPNAV_ALT_HOLD_ACCEL_MAX 250.0f // hard coded copy of throttle controller's maximum acceleration in cm/s. To-Do: remove duplication with throttle controller definition
|
||||
|
||||
#define WPNAV_MIN_LEASH_LENGTH 100.0f // minimum leash lengths in cm
|
||||
#define WPNAV_LEASH_LENGTH_MIN 100.0f // minimum leash lengths in cm
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
# define WPNAV_LOITER_UPDATE_TIME 0.020f // 50hz update rate on high speed CPUs (Pixhawk, Flymaple)
|
||||
|
Loading…
Reference in New Issue
Block a user