Sub: Solve some typos

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2017-10-18 22:36:37 -02:00 committed by jaxxzer
parent bb2573f945
commit 1598a97734
6 changed files with 11 additions and 11 deletions

View File

@ -69,7 +69,7 @@ Other changes:
- Implement battery failsafe - Implement battery failsafe
- Implement relay joystick button functions - Implement relay joystick button functions
- Add joystick button functions to control servos - Add joystick button functions to control servos
- Add joystick button function to toggle between foward/lateral input and roll/pitch input - Add joystick button function to toggle between forward/lateral input and roll/pitch input
- Remove BASE_RESET and BASE_PRESS baro parameters. Barometer reset is now done via mavlink cmd. - Remove BASE_RESET and BASE_PRESS baro parameters. Barometer reset is now done via mavlink cmd.
- Implement parameter reset to defaults via mavlink cmd. - Implement parameter reset to defaults via mavlink cmd.
- Fixed bug with camera tilt smoothing conflicting with RC_OVERRIDE messages - Fixed bug with camera tilt smoothing conflicting with RC_OVERRIDE messages
@ -327,7 +327,7 @@ Changes from 3.3-rc3
b) H_COLYAW param can be float b) H_COLYAW param can be float
8) Small Improvements / Bug Fixes: 8) Small Improvements / Bug Fixes:
a) reduced spline overshoot after very long track followed by very short track a) reduced spline overshoot after very long track followed by very short track
b) log entire mission to dataflash whenver it's uploaded b) log entire mission to dataflash whenever it's uploaded
c) altitude reported if vehicle takes off before GPS lock c) altitude reported if vehicle takes off before GPS lock
d) high speed logging of IMU d) high speed logging of IMU
e) STOP flight mode renamed to BRAKE and aux switch option added e) STOP flight mode renamed to BRAKE and aux switch option added
@ -481,7 +481,7 @@ Changes from 3.2-rc7
3) sensor health flags sent to GCS only after initialisation to remove false alerts 3) sensor health flags sent to GCS only after initialisation to remove false alerts
4) suppress bad terrain data alerts 4) suppress bad terrain data alerts
5) Bug Fix: 5) Bug Fix:
a)PX4 dataflash RAM useage reduced to 8k so it works again a)PX4 dataflash RAM usage reduced to 8k so it works again
------------------------------------------------------------------ ------------------------------------------------------------------
ArduCopter 3.2-rc7 04-Sep-2014 ArduCopter 3.2-rc7 04-Sep-2014
Changes from 3.2-rc6 Changes from 3.2-rc6
@ -708,7 +708,7 @@ ArduCopter 3.1-rc6 16-Nov-2013
Improvements over 3.1-rc5 Improvements over 3.1-rc5
1) Heli improvements: 1) Heli improvements:
a) support for direct drive tails (uses TAIL_TYPE and TAIL_SPEED parameters) a) support for direct drive tails (uses TAIL_TYPE and TAIL_SPEED parameters)
b) smooth main rotor ramp-up for those without external govenor (RSC_RAMP_TIME) b) smooth main rotor ramp-up for those without external governor (RSC_RAMP_TIME)
c) internal estimate of rotor speed configurable with RSC_RUNUP_TIME parameter to ensure rotor at top speed before starting missions c) internal estimate of rotor speed configurable with RSC_RUNUP_TIME parameter to ensure rotor at top speed before starting missions
d) LAND_COL_MIN collective position used when landed (reduces chance copter will push too hard into the ground when landing or before starting missions) d) LAND_COL_MIN collective position used when landed (reduces chance copter will push too hard into the ground when landing or before starting missions)
e) reduced collective while in stabilize mode (STAB_COL_MIN, STAB_COL_MAX) for more precise throttle control e) reduced collective while in stabilize mode (STAB_COL_MIN, STAB_COL_MAX) for more precise throttle control
@ -843,7 +843,7 @@ Improvements over 3.0.0-rc3
6) RTL returns to initial yaw heading before descending 6) RTL returns to initial yaw heading before descending
7) safe features: 7) safe features:
i) check for gps lock when entering failsafe i) check for gps lock when entering failsafe
ii) pre-arm check for mag field lenght ii) pre-arm check for mag field length
iii) pre-arm check for board voltage between 4.5v ~ 5.8V iii) pre-arm check for board voltage between 4.5v ~ 5.8V
iv) beep twice during arming iv) beep twice during arming
v) GPS failsafe enabled by default (will LAND if loses GPS in Loiter, AUTO, Guided modes) v) GPS failsafe enabled by default (will LAND if loses GPS in Loiter, AUTO, Guided modes)
@ -943,7 +943,7 @@ Improvements over 2.9-rc3:
ArduCopter 2.9-rc3 11-Jan-2013 ArduCopter 2.9-rc3 11-Jan-2013
Improvements over 2.9-rc2: Improvements over 2.9-rc2:
1) alt hold with sonar improvements - now on by default (Leonard/Randy) 1) alt hold with sonar improvements - now on by default (Leonard/Randy)
2) performance and memory useage improvements (Tridge/Randy) 2) performance and memory usage improvements (Tridge/Randy)
3) increase APM1 baro pressure read from 5hz to 8.3hz to improve alt hold (Randy) 3) increase APM1 baro pressure read from 5hz to 8.3hz to improve alt hold (Randy)
4) bug fix: altitude error reported to GCS (Randy) 4) bug fix: altitude error reported to GCS (Randy)
5) limit inertial nav's max accel offset correction to 100cm/s/s to speed up recovery after hard impacts (Randy)_ 5) limit inertial nav's max accel offset correction to 100cm/s/s to speed up recovery after hard impacts (Randy)_

View File

@ -163,7 +163,7 @@ bool Sub::start_command(const AP_Mission::Mission_Command& cmd)
// Verify command Handlers // Verify command Handlers
/********************************************************************************/ /********************************************************************************/
// check to see if current command goal has been acheived // check to see if current command goal has been achieved
// called by mission library in mission.update() // called by mission library in mission.update()
bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd) bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd)
{ {

View File

@ -282,7 +282,7 @@ enum RTLState {
// Leak failsafe definitions (FS_LEAK_ENABLE parameter) // Leak failsafe definitions (FS_LEAK_ENABLE parameter)
#define FS_LEAK_DISABLED 0 // Disabled #define FS_LEAK_DISABLED 0 // Disabled
#define FS_LEAK_WARN_ONLY 1 // Only send waring to gcs #define FS_LEAK_WARN_ONLY 1 // Only send warning to gcs
#define FS_LEAK_SURFACE 2 // Switch to surface mode #define FS_LEAK_SURFACE 2 // Switch to surface mode
// Internal pressure failsafe threshold (FS_PRESS_MAX parameter) // Internal pressure failsafe threshold (FS_PRESS_MAX parameter)

View File

@ -287,7 +287,7 @@ void Sub::failsafe_internal_temperature_check()
} }
} }
// Check if we are leaking and perform appropiate action // Check if we are leaking and perform appropriate action
void Sub::failsafe_leak_check() void Sub::failsafe_leak_check()
{ {
bool status = leak_detector.get_status(); bool status = leak_detector.get_status();

View File

@ -1,7 +1,7 @@
#include "Sub.h" #include "Sub.h"
// change flight mode and perform any necessary initialisation // change flight mode and perform any necessary initialisation
// returns true if mode was succesfully set // returns true if mode was successfully set
bool Sub::set_mode(control_mode_t mode, mode_reason_t reason) bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
{ {
// boolean to record if flight mode could be set // boolean to record if flight mode could be set

View File

@ -229,7 +229,7 @@ void Sub::startup_INS_ground()
ahrs.reset(); ahrs.reset();
} }
// calibrate gyros - returns true if succesfully calibrated // calibrate gyros - returns true if successfully calibrated
bool Sub::calibrate_gyros() bool Sub::calibrate_gyros()
{ {
// gyro offset calibration // gyro offset calibration