SITL: correct typos in comments

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2022-01-10 13:44:34 +01:00 committed by Randy Mackay
parent 4c72d0f562
commit 87b0db7990
2 changed files with 4 additions and 4 deletions

View File

@ -98,7 +98,7 @@ private:
// battery capacity in Ah. Use zero for unlimited
float battCapacityAh = 0.0;
// CTUN.ThO at bover at refAlt
// CTUN.ThO at hover at refAlt
float hoverThrOut = 0.39;
// MOT_THST_EXPO
@ -121,7 +121,7 @@ private:
float slew_max = 150;
// rotor disc area in m**2 for 4 x 0.35m dia rotors
// Note that coaxial rotors count as one rotor only when cauclating effective disc area
// Note that coaxial rotors count as one rotor only when calculating effective disc area
float disc_area = 0.385;
// momentum drag coefficient

View File

@ -174,7 +174,7 @@ public:
AP_Int8 mag_fail[HAL_COMPASS_MAX_SENSORS]; // fail magnetometer, 1 for no data, 2 for freeze
AP_Float servo_speed; // servo speed in seconds
AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
AP_Float sonar_glitch;// probability between 0-1 that any given sonar sample will read as max distance
AP_Float sonar_noise; // in metres
AP_Float sonar_scale; // meters per volt
@ -215,7 +215,7 @@ public:
AP_Int8 terrain_enable; // enable using terrain for height
AP_Int16 pin_mask; // for GPIO emulation
AP_Float speedup; // simulation speedup
AP_Int8 odom_enable; // enable visual odomotry data
AP_Int8 odom_enable; // enable visual odometry data
AP_Int8 telem_baudlimit_enable; // enable baudrate limiting on links
AP_Float flow_noise; // optical flow measurement noise (rad/sec)
AP_Int8 baro_count; // number of simulated baros to create