mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_AttitudeControl: Set the gravitational acceleration value to the defined value
This commit is contained in:
parent
219dc2e7da
commit
d7533843d5
@ -16,7 +16,7 @@
|
||||
// position controller default definitions
|
||||
#define POSCONTROL_ACCELERATION_MIN 50.0f // minimum horizontal acceleration in cm/s/s - used for sanity checking acceleration in leash length calculation
|
||||
#define POSCONTROL_ACCEL_XY 100.0f // default horizontal acceleration in cm/s/s. This is overwritten by waypoint and loiter controllers
|
||||
#define POSCONTROL_ACCEL_XY_MAX 980.0f // max horizontal acceleration in cm/s/s that the position velocity controller will ask from the lower accel controller
|
||||
#define POSCONTROL_ACCEL_XY_MAX (GRAVITY_MSS*100) // max horizontal acceleration in cm/s/s that the position velocity controller will ask from the lower accel controller
|
||||
#define POSCONTROL_STOPPING_DIST_UP_MAX 300.0f // max stopping distance (in cm) vertically while climbing
|
||||
#define POSCONTROL_STOPPING_DIST_DOWN_MAX 200.0f // max stopping distance (in cm) vertically while descending
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user