From e8b5fd4c709079c5d461585eb483f9b87630894a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Mon, 25 Mar 2019 20:48:59 -0300 Subject: [PATCH] Rover: Fix typos MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- APMrover2/AP_MotorsUGV.cpp | 2 +- APMrover2/radio.cpp | 2 +- APMrover2/sailboat.cpp | 2 +- APMrover2/system.cpp | 6 +++--- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/APMrover2/AP_MotorsUGV.cpp b/APMrover2/AP_MotorsUGV.cpp index a88af59c78..3a57260cdb 100644 --- a/APMrover2/AP_MotorsUGV.cpp +++ b/APMrover2/AP_MotorsUGV.cpp @@ -107,7 +107,7 @@ AP_MotorsUGV::AP_MotorsUGV(AP_ServoRelayEvents &relayEvents) : void AP_MotorsUGV::init() { - // setup servo ouput + // setup servo output setup_servo_output(); // setup pwm type diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 0963d8f780..f12f2bb576 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -15,7 +15,7 @@ void Rover::set_control_channels(void) channel_throttle->set_angle(100); channel_lateral->set_angle(100); - // Allow to reconfigure ouput when not armed + // Allow to reconfigure output when not armed if (!arming.is_armed()) { g2.motors.setup_servo_output(); // For a rover safety is TRIM throttle diff --git a/APMrover2/sailboat.cpp b/APMrover2/sailboat.cpp index 83fb37eeca..abc8062f3e 100644 --- a/APMrover2/sailboat.cpp +++ b/APMrover2/sailboat.cpp @@ -6,7 +6,7 @@ To Do List - Improve tacking in light winds and bearing away in strong wings - consider drag vs lift sailing differences, ie upwind sail is like wing, dead down wind sail is like parachute - - max speed paramiter and contoller, for maping you may not want to go too fast + - max speed paramiter and controller, for mapping you may not want to go too fast - mavlink sailing messages - motor sailing, some boats may also have motor, we need to decide at what point we would be better of just motoring in low wind, or for a tight loiter, or to hit waypoint exactly, or if stuck head to wind, or to reverse... - smart decision making, ie tack on windshifts, what to do if stuck head to wind diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 14deb1a3b9..ef5e21e8c7 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -113,7 +113,7 @@ void Rover::init_ardupilot() ins.set_log_raw_bit(MASK_LOG_IMU_RAW); - set_control_channels(); // setup radio channels and ouputs ranges + set_control_channels(); // setup radio channels and outputs ranges init_rc_in(); // sets up rc channels deadzone g2.motors.init(); // init motors including setting servo out channels ranges SRV_Channels::enable_aux_servos(); @@ -271,7 +271,7 @@ void Rover::startup_INS_ground(void) hal.scheduler->delay(100); ahrs.init(); - // say to EKF that rover only move by goind forward + // say to EKF that rover only move by going forward ahrs.set_fly_forward(true); ahrs.set_vehicle_class(AHRS_VEHICLE_GROUND); @@ -287,7 +287,7 @@ void Rover::notify_mode(const Mode *mode) } /* - check a digitial pin for high,low (1/0) + check a digital pin for high,low (1/0) */ uint8_t Rover::check_digital_pin(uint8_t pin) {