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),
|
||||
|
@ -400,7 +400,7 @@ bool AC_PrecLand::target_acquired()
|
|||
{
|
||||
if ((AP_HAL::millis()-_last_update_ms) > LANDING_TARGET_TIMEOUT_MS) {
|
||||
if (_target_acquired) {
|
||||
// just lost the landing target, inform the user. This message will only be sent once everytime target is lost
|
||||
// just lost the landing target, inform the user. This message will only be sent once every time target is lost
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PrecLand: Target Lost");
|
||||
}
|
||||
// not had a sensor update since a long time
|
||||
|
@ -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,11 +7,11 @@
|
|||
#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
|
||||
|
||||
// Initialize the state machine. This is called everytime vehicle switches mode
|
||||
// Initialize the state machine. This is called every time vehicle switches mode
|
||||
void AC_PrecLand_StateMachine::init()
|
||||
{
|
||||
AC_PrecLand *_precland = AP::ac_precland();
|
||||
|
@ -24,14 +24,14 @@ 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
|
||||
reset_failed_landing_statemachine();
|
||||
}
|
||||
|
||||
// Reset the landing statemachines. This needs to be called everytime the landing target is back in sight.
|
||||
// Reset the landing statemachines. This needs to be called every time the landing target is back in sight.
|
||||
// So that if the landing target goes out of sight again, we can start the failed landing procedure back from the beginning stage
|
||||
void AC_PrecLand_StateMachine::reset_failed_landing_statemachine()
|
||||
{
|
||||
|
|
|
@ -23,7 +23,7 @@ public:
|
|||
// Do not allow copies
|
||||
CLASS_NO_COPY(AC_PrecLand_StateMachine);
|
||||
|
||||
// Initialize the state machine. This is called everytime vehicle switches mode
|
||||
// Initialize the state machine. This is called every time vehicle switches mode
|
||||
void init();
|
||||
|
||||
// Current status of the precland state machine
|
||||
|
@ -78,7 +78,7 @@ private:
|
|||
// Vector3f "retry_pos_m" is filled with the required location.
|
||||
Status retry_landing(Vector3f &retry_pos_m);
|
||||
|
||||
// Reset the landing statemachine. This needs to be called everytime the landing target is back in sight.
|
||||
// Reset the landing statemachine. This needs to be called every time the landing target is back in sight.
|
||||
// So that if the landing target goes out of sight again, we can start the failed landing procedure back from the beginning stage
|
||||
void reset_failed_landing_statemachine();
|
||||
|
||||
|
|
Loading…
Reference in New Issue