More spelling stuff

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-01-06 17:15:35 +01:00 committed by Tom Pittenger
parent 8419045aea
commit d408d25f92
7 changed files with 18 additions and 16 deletions

View File

@ -51,7 +51,7 @@ const AP_Param::GroupInfo AP_Gripper::var_info[] = {
// @DisplayName: Gripper Regrab interval // @DisplayName: Gripper Regrab interval
// @Description: Time in seconds that gripper will regrab the cargo to ensure grip has not weakened; 0 to disable // @Description: Time in seconds that gripper will regrab the cargo to ensure grip has not weakened; 0 to disable
// @User: Advanced // @User: Advanced
// @Values: 0 255 // @Range: 0 255
// @Units: seconds // @Units: seconds
AP_GROUPINFO("REGRAB", 5, AP_Gripper, config.regrab_interval, GRIPPER_REGRAB_DEFAULT), AP_GROUPINFO("REGRAB", 5, AP_Gripper, config.regrab_interval, GRIPPER_REGRAB_DEFAULT),

View File

@ -485,7 +485,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Param: TERR_GRAD // @Param: TERR_GRAD
// @DisplayName: Maximum terrain gradient // @DisplayName: Maximum terrain gradient
// @Description: Specifies the maxium gradient of the terrain below the vehicle when it is using range finder as a height reference // @Description: Specifies the maximum gradient of the terrain below the vehicle when it is using range finder as a height reference
// @Range: 0 0.2 // @Range: 0 0.2
// @Increment: 0.01 // @Increment: 0.01
// @User: Advanced // @User: Advanced

View File

@ -717,10 +717,10 @@ void NavEKF2_core::FuseMagnetometer()
* Fuse magnetic heading measurement using explicit algebraic equations generated with Matlab symbolic toolbox. * Fuse magnetic heading measurement using explicit algebraic equations generated with Matlab symbolic toolbox.
* The script file used to generate these and other equations in this filter can be found here: * The script file used to generate these and other equations in this filter can be found here:
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
* This fusion method only modifies the orientation, does not require use of the magnetic field states and is computatonally cheaper. * This fusion method only modifies the orientation, does not require use of the magnetic field states and is computationally cheaper.
* It is suitable for use when the external magnetic field environment is disturbed (eg close to metal structures, on ground). * It is suitable for use when the external magnetic field environment is disturbed (eg close to metal structures, on ground).
* It is not as robust to magneometer failures. * It is not as robust to magnetometer failures.
* It is not suitable for operation where the horizontal magnetic field strength is weak (within 30 degreees latitude of the the magnetic poles) * It is not suitable for operation where the horizontal magnetic field strength is weak (within 30 degrees latitude of the the magnetic poles)
*/ */
void NavEKF2_core::fuseEulerYaw() void NavEKF2_core::fuseEulerYaw()
{ {

View File

@ -1,3 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
@ -195,7 +197,7 @@ void NavEKF2_core::ResetHeight(void)
bool NavEKF2_core::resetHeightDatum(void) bool NavEKF2_core::resetHeightDatum(void)
{ {
if (activeHgtSource == HGT_SOURCE_RNG) { if (activeHgtSource == HGT_SOURCE_RNG) {
// by definition the height dataum is at ground level so cannot perform the reset // by definition the height datum is at ground level so cannot perform the reset
return false; return false;
} }
// record the old height estimate // record the old height estimate
@ -204,7 +206,7 @@ bool NavEKF2_core::resetHeightDatum(void)
frontend->_baro.update_calibration(); frontend->_baro.update_calibration();
// reset the height state // reset the height state
stateStruct.position.z = 0.0f; stateStruct.position.z = 0.0f;
// adjust the height of the EKF origin so that the origin plus baro height before and afer the reset is the same // adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
if (validOrigin) { if (validOrigin) {
EKF_origin.alt += oldHgt*100; EKF_origin.alt += oldHgt*100;
} }

View File

@ -475,7 +475,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
// @Param: TERR_GRAD // @Param: TERR_GRAD
// @DisplayName: Maximum terrain gradient // @DisplayName: Maximum terrain gradient
// @Description: Specifies the maxium gradient of the terrain below the vehicle when it is using range finder as a height reference // @Description: Specifies the maximum gradient of the terrain below the vehicle when it is using range finder as a height reference
// @Range: 0 0.2 // @Range: 0 0.2
// @Increment: 0.01 // @Increment: 0.01
// @User: Advanced // @User: Advanced
@ -518,7 +518,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
// @Param: ACC_BIAS_LIM // @Param: ACC_BIAS_LIM
// @DisplayName: Accelerometer bias limit // @DisplayName: Accelerometer bias limit
// @Description: The accelerometer bias state will be limited to +- this vlaue // @Description: The accelerometer bias state will be limited to +- this value
// @Range: 0.5 2.5 // @Range: 0.5 2.5
// @Increment: 0.1 // @Increment: 0.1
// @User: Advanced // @User: Advanced
@ -796,7 +796,7 @@ void NavEKF3::getVelNED(int8_t instance, Vector3f &vel)
} }
} }
// Return the rate of change of vertical position in the down diection (dPosD/dt) in m/s // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
float NavEKF3::getPosDownDerivative(int8_t instance) float NavEKF3::getPosDownDerivative(int8_t instance)
{ {
if (instance < 0 || instance >= num_cores) instance = primary; if (instance < 0 || instance >= num_cores) instance = primary;
@ -976,7 +976,7 @@ bool NavEKF3::getOriginLLH(struct Location &loc) const
} }
// set the latitude and longitude and height used to set the NED origin // set the latitude and longitude and height used to set the NED origin
// All NED positions calcualted by the filter will be relative to this location // All NED positions calculated by the filter will be relative to this location
// The origin cannot be set if the filter is in a flight mode (eg vehicle armed) // The origin cannot be set if the filter is in a flight mode (eg vehicle armed)
// Returns false if the filter has rejected the attempt to set the origin // Returns false if the filter has rejected the attempt to set the origin
bool NavEKF3::setOriginLLH(struct Location &loc) bool NavEKF3::setOriginLLH(struct Location &loc)

View File

@ -702,10 +702,10 @@ void NavEKF3_core::FuseMagnetometer()
* Fuse magnetic heading measurement using explicit algebraic equations generated with Matlab symbolic toolbox. * Fuse magnetic heading measurement using explicit algebraic equations generated with Matlab symbolic toolbox.
* The script file used to generate these and other equations in this filter can be found here: * The script file used to generate these and other equations in this filter can be found here:
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
* This fusion method only modifies the orientation, does not require use of the magnetic field states and is computatonally cheaper. * This fusion method only modifies the orientation, does not require use of the magnetic field states and is computationally cheaper.
* It is suitable for use when the external magnetic field environment is disturbed (eg close to metal structures, on ground). * It is suitable for use when the external magnetic field environment is disturbed (eg close to metal structures, on ground).
* It is not as robust to magneometer failures. * It is not as robust to magnetometer failures.
* It is not suitable for operation where the horizontal magnetic field strength is weak (within 30 degreees latitude of the the magnetic poles) * It is not suitable for operation where the horizontal magnetic field strength is weak (within 30 degrees latitude of the the magnetic poles)
*/ */
void NavEKF3_core::fuseEulerYaw() void NavEKF3_core::fuseEulerYaw()
{ {

View File

@ -197,7 +197,7 @@ void NavEKF3_core::ResetHeight(void)
bool NavEKF3_core::resetHeightDatum(void) bool NavEKF3_core::resetHeightDatum(void)
{ {
if (activeHgtSource == HGT_SOURCE_RNG) { if (activeHgtSource == HGT_SOURCE_RNG) {
// by definition the height dataum is at ground level so cannot perform the reset // by definition the height datum is at ground level so cannot perform the reset
return false; return false;
} }
// record the old height estimate // record the old height estimate
@ -206,7 +206,7 @@ bool NavEKF3_core::resetHeightDatum(void)
frontend->_baro.update_calibration(); frontend->_baro.update_calibration();
// reset the height state // reset the height state
stateStruct.position.z = 0.0f; stateStruct.position.z = 0.0f;
// adjust the height of the EKF origin so that the origin plus baro height before and afer the reset is the same // adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
if (validOrigin) { if (validOrigin) {
EKF_origin.alt += oldHgt*100; EKF_origin.alt += oldHgt*100;
} }