mirror of https://github.com/ArduPilot/ardupilot
AC_PrecLand: Fix some typos
Fixed some typos found in the code.
This commit is contained in:
parent
df88281e07
commit
b50635d27d
|
@ -150,7 +150,7 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
|
|||
|
||||
// @Param: TIMEOUT
|
||||
// @DisplayName: PrecLand retry timeout
|
||||
// @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attemp a landing retry depending on PLND_STRICT parameter.
|
||||
// @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT parameter.
|
||||
// @Range: 0 20
|
||||
// @Units: s
|
||||
AP_GROUPINFO("TIMEOUT", 13, AC_PrecLand, _retry_timeout_sec, 4),
|
||||
|
@ -622,7 +622,7 @@ bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body)
|
|||
}
|
||||
|
||||
|
||||
// rotate vector based on sensor oriention to get correct body frame vector
|
||||
// rotate vector based on sensor orientation to get correct body frame vector
|
||||
if (_orient != ROTATION_PITCH_270) {
|
||||
// by default, the vector is constructed downwards in body frame
|
||||
// hence, we do not do any rotation if the orientation is downwards
|
||||
|
|
|
@ -188,7 +188,7 @@ private:
|
|||
AP_Float _xy_max_dist_desc; // Vehicle doing prec land will only descent vertically when horizontal error (in m) is below this limit
|
||||
AP_Int8 _strict; // PrecLand strictness
|
||||
AP_Int8 _retry_max; // PrecLand Maximum number of retires to a failed landing
|
||||
AP_Float _retry_timeout_sec; // Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attemp a landing retry depending on PLND_STRICT param.
|
||||
AP_Float _retry_timeout_sec; // Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT param.
|
||||
AP_Int8 _retry_behave; // Action to do when trying a landing retry
|
||||
AP_Float _sensor_min_alt; // PrecLand minimum height required for detecting target
|
||||
AP_Float _sensor_max_alt; // PrecLand maximum height the sensor can detect target
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
static const float MAX_POS_ERROR_M = 0.75f; // Maximum possition error for retry locations
|
||||
static const float MAX_POS_ERROR_M = 0.75f; // Maximum position error for retry locations
|
||||
static const uint32_t FAILSAFE_INIT_TIMEOUT_MS = 7000; // Timeout in ms before failsafe measures are started. During this period vehicle is completely stopped to give user the time to take over
|
||||
static const float RETRY_OFFSET_ALT_M = 1.5f; // This gets added to the altitude of the retry location
|
||||
|
||||
|
@ -24,7 +24,7 @@ void AC_PrecLand_StateMachine::init()
|
|||
// precland is not enabled, prec land state machine methods should not be called!
|
||||
return;
|
||||
}
|
||||
// init is only called ONCE per mode change. So in a particuar mode we can retry only a finite times.
|
||||
// init is only called ONCE per mode change. So in a particular mode we can retry only a finite times.
|
||||
// The counter will be reset if the statemachine is called from a different mode
|
||||
_retry_count = 0;
|
||||
// reset every other statemachine
|
||||
|
|
Loading…
Reference in New Issue