mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_WPNav: minor comment and formatting changes
This commit is contained in:
parent
fd55068620
commit
39213584da
@ -81,7 +81,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
|
||||
|
||||
// @Param: LOIT_MAXA
|
||||
// @DisplayName: Loiter maximum acceleration
|
||||
// @Description: Loiter maximum acceleration in cm/s/s
|
||||
// @Description: Loiter maximum acceleration in cm/s/s. Higher values cause the copter to accelerate and stop more quickly.
|
||||
// @Units: cm/s/s
|
||||
// @Range: 100 981
|
||||
// @Increment: 1
|
||||
@ -90,7 +90,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
|
||||
|
||||
// @Param: LOIT_MINA
|
||||
// @DisplayName: Loiter minimum acceleration
|
||||
// @Description: Loiter minimum acceleration in cm/s/s
|
||||
// @Description: Loiter minimum acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered, but cause a larger jerk when the copter stops.
|
||||
// @Units: cm/s/s
|
||||
// @Range: 100 981
|
||||
// @Increment: 1
|
||||
|
@ -277,8 +277,8 @@ protected:
|
||||
// parameters
|
||||
AP_Float _loiter_speed_cms; // maximum horizontal speed in cm/s while in loiter
|
||||
AP_Float _loiter_jerk_max_cmsss; // maximum jerk in cm/s/s/s while in loiter
|
||||
AP_Float _loiter_accel_cmss; // loiter's acceleration in cm/s/s
|
||||
AP_Float _loiter_accel_min_cmss; // loiter's acceleration in cm/s/s
|
||||
AP_Float _loiter_accel_cmss; // loiter's max acceleration in cm/s/s
|
||||
AP_Float _loiter_accel_min_cmss; // loiter's min acceleration in cm/s/s
|
||||
AP_Float _wp_speed_cms; // maximum horizontal speed in cm/s during missions
|
||||
AP_Float _wp_speed_up_cms; // climb speed target in cm/s
|
||||
AP_Float _wp_speed_down_cms; // descent speed target in cm/s
|
||||
|
Loading…
Reference in New Issue
Block a user