more spelling mistakes

This commit is contained in:
nopeppermint 2016-01-10 12:41:04 +01:00 committed by Lorenz Meier
parent ed081ef60b
commit 78f9bb79f1
13 changed files with 15 additions and 15 deletions

View File

@ -281,7 +281,7 @@ TYPEDEF_HIDES_STRUCT = NO
# causing a significant performance penality.
# If the system has enough physical memory increasing the cache will improve the
# performance by keeping more symbols in memory. Note that the value works on
# a logarithmic scale so increasing the size by one will rougly double the
# a logarithmic scale so increasing the size by one will roughly double the
# memory usage. The cache size is given by this formula:
# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0,
# corresponding to a cache size of 2^16 = 65536 symbols

View File

@ -51,7 +51,7 @@ enum LaunchDetectionResult {
up and still be set to 'throttlePreTakeoff'.
For instance this is used to have a delay for the motor
when launching a fixed wing aircraft from a bungee */
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, teh controller should control
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, the controller should control
attitude and also throttle up the motors. */
};

View File

@ -54,7 +54,7 @@
PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
/**
* Catapult accelerometer theshold.
* Catapult accelerometer threshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*
@ -64,7 +64,7 @@ PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
/**
* Catapult time theshold.
* Catapult time threshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*

View File

@ -615,7 +615,7 @@ sbus_decode(uint64_t frame_time, uint8_t *frame, uint16_t *values, uint16_t *num
*
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
* condition as fail-safe greatly reduces the reliability and range of the radio link,
* e.g. by prematurely issueing return-to-launch!!! */
* e.g. by prematurely issuing return-to-launch!!! */
*sbus_failsafe = false;
*sbus_frame_drop = true;

View File

@ -2,7 +2,7 @@ function [xa_apo,Pa_apo,Rot_matrix,eulerAngles,debugOutput]...
= AttitudeEKF(approx_prediction,use_inertia_matrix,zFlag,dt,z,q_rotSpeed,q_rotAcc,q_acc,q_mag,r_gyro,r_accel,r_mag,J)
%LQG Postion Estimator and Controller
%LQG Position Estimator and Controller
% Observer:
% x[n|n] = x[n|n-1] + M(y[n] - Cx[n|n-1] - Du[n])
% x[n+1|n] = Ax[n|n] + Bu[n]

View File

@ -499,7 +499,7 @@ void AttitudeEKF(unsigned char approx_prediction, unsigned char
float b_z[6];
/* LQG Postion Estimator and Controller */
/* LQG Position Estimator and Controller */
/* Observer: */
/* x[n|n] = x[n|n-1] + M(y[n] - Cx[n|n-1] - Du[n]) */
/* x[n+1|n] = Ax[n|n] + Bu[n] */

View File

@ -75,11 +75,11 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
} ArmingTransitionVolatileState_t;
// This structure represents a test case for arming_state_transition. It contains the machine
// state prior to transtion, the requested state to transition to and finally the expected
// state prior to transition, the requested state to transition to and finally the expected
// machine state after transition.
typedef struct {
const char* assertMsg; // Text to show when test case fails
ArmingTransitionVolatileState_t current_state; // Machine state prior to transtion
ArmingTransitionVolatileState_t current_state; // Machine state prior to transition
hil_state_t hil_state; // Current vehicle_status_s.hil_state
bool condition_system_sensors_initialized; // Current vehicle_status_s.condition_system_sensors_initialized
bool safety_switch_available; // Current safety_s.safety_switch_available

View File

@ -145,7 +145,7 @@ private:
// predict the next state
void predict();
// correct the state prediction wtih a measurement
// correct the state prediction with a measurement
void correctBaro();
void correctGps();
void correctLidar();

View File

@ -35,7 +35,7 @@
#include <algorithm>
#include <drivers/drv_hrt.h>
// static intialization.
// static initialization.
uORB::FastRpcChannel uORB::FastRpcChannel::_Instance;
static unsigned long _dropped_pkts;

View File

@ -44,7 +44,7 @@ uORB::KraitFastRpcChannel uORB::KraitFastRpcChannel::_Instance;
static void DumpData(uint8_t *buffer, int32_t length, int32_t num_topics);
// static intialization.
// static initialization.
static std::string _log_file_name = "./hex_dump.txt";
static unsigned long _snd_msg_min = 0xFFFFFF;

View File

@ -481,7 +481,7 @@ public:
* compared to thrust.
* @param yaw_wcale Scaling factor applied to yaw inputs compared
* to thrust.
* @param idle_speed Minumum rotor control output value; usually
* @param idle_speed Minimum rotor control output value; usually
* tuned to ensure that rotors never stall at the
* low end of their control range.
*/

View File

@ -118,7 +118,7 @@ extern uint32_t _etext;
* This function should then be called in the application-specific
* user_start logic in order to perform the C++ initialization. NOTE
* that no component of the core NuttX RTOS logic is involved; This
* function defintion only provides the 'contract' between application
* function definition only provides the 'contract' between application
* specific C++ code and platform-specific toolchain support
*
***************************************************************************/

View File

@ -1058,7 +1058,7 @@ always used with the `users_by_name` hash table).
Several sort orders
~~~~~~~~~~~~~~~~~~~
It comes as no suprise that two hash tables can have different sort orders, but
It comes as no surprise that two hash tables can have different sort orders, but
this fact can also be used advantageously to sort the 'same items' in several
ways. This is based on the ability to store a structure in several hash tables.