mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: Fix Bug to use WPNAV_ACCEL_C
This commit is contained in:
parent
59bd27519a
commit
be7d550d5e
|
@ -87,7 +87,7 @@ public:
|
|||
float get_wp_acceleration() const { return (is_positive(_wp_accel_cmss)) ? _wp_accel_cmss : WPNAV_ACCELERATION; }
|
||||
|
||||
/// get_wp_acceleration - returns acceleration in cm/s/s during missions
|
||||
float get_corner_acceleration() const { return (is_positive(_wp_accel_c_cmss)) ? _wp_accel_cmss : get_wp_acceleration(); }
|
||||
float get_corner_acceleration() const { return (is_positive(_wp_accel_c_cmss)) ? _wp_accel_c_cmss : get_wp_acceleration(); }
|
||||
|
||||
/// get_wp_destination waypoint using position vector
|
||||
/// x,y are distance from ekf origin in cm
|
||||
|
|
Loading…
Reference in New Issue