mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
WPNav: reduce max acceleration to 2.5m/s
Also includes bug fix to ramp up of speed of intermediate point
This commit is contained in:
parent
635b3fabda
commit
4704b729c2
@ -287,6 +287,9 @@ void AC_WPNav::set_origin_and_destination(const Vector3f& origin, const Vector3f
|
||||
_track_desired = 0;
|
||||
_target = origin;
|
||||
_reached_destination = false;
|
||||
|
||||
// reset limited speed to zero to slow initial acceleration away from wp
|
||||
_limited_speed_xy_cms = 0;
|
||||
}
|
||||
|
||||
/// advance_target_along_track - move target location along track from origin to destination
|
||||
|
@ -12,7 +12,7 @@
|
||||
|
||||
// loiter maximum velocities and accelerations
|
||||
#define WPNAV_LOITER_SPEED 750.0f // maximum default loiter speed in cm/s
|
||||
#define MAX_LOITER_POS_ACCEL 500.0f // defines the velocity vs distant curve. maximum acceleration in cm/s/s that loiter position controller asks for from acceleration controller
|
||||
#define MAX_LOITER_POS_ACCEL 250.0f // defines the velocity vs distant curve. maximum acceleration in cm/s/s that loiter position controller asks for from acceleration controller
|
||||
#define MAX_LOITER_VEL_ACCEL 800.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 MAX_LOITER_POS_ACCEL.
|
||||
// max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s
|
||||
@ -28,7 +28,7 @@
|
||||
#define WPNAV_ALT_HOLD_P 2.0f // hard coded estimate of throttle controller's altitude hold's P gain. To-Do: retrieve gain from throttle controller
|
||||
#define WPNAV_ALT_HOLD_ACCEL_MAX 250.0f // hard coded estimate of throttle controller's maximum acceleration in cm/s. To-Do: retrieve from throttle controller
|
||||
|
||||
#define WPNAV_WP_ACCELERATION 200.0f // acceleration in cm/s/s used to increase the speed of the intermediate point up to it's maximum speed held in _speed_xy_cms
|
||||
#define WPNAV_WP_ACCELERATION 500.0f // acceleration in cm/s/s used to increase the speed of the intermediate point up to it's maximum speed held in _speed_xy_cms
|
||||
|
||||
class AC_WPNav
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user