Browse Source

Rover: Fix typos

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
master
Patrick José Pereira 6 years ago committed by Randy Mackay
parent
commit
e8b5fd4c70
  1. 2
      APMrover2/AP_MotorsUGV.cpp
  2. 2
      APMrover2/radio.cpp
  3. 2
      APMrover2/sailboat.cpp
  4. 6
      APMrover2/system.cpp

2
APMrover2/AP_MotorsUGV.cpp

@ -107,7 +107,7 @@ AP_MotorsUGV::AP_MotorsUGV(AP_ServoRelayEvents &relayEvents) :
void AP_MotorsUGV::init() void AP_MotorsUGV::init()
{ {
// setup servo ouput // setup servo output
setup_servo_output(); setup_servo_output();
// setup pwm type // setup pwm type

2
APMrover2/radio.cpp

@ -15,7 +15,7 @@ void Rover::set_control_channels(void)
channel_throttle->set_angle(100); channel_throttle->set_angle(100);
channel_lateral->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()) { if (!arming.is_armed()) {
g2.motors.setup_servo_output(); g2.motors.setup_servo_output();
// For a rover safety is TRIM throttle // For a rover safety is TRIM throttle

2
APMrover2/sailboat.cpp

@ -6,7 +6,7 @@
To Do List To Do List
- Improve tacking in light winds and bearing away in strong wings - 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 - 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 - 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... - 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 - smart decision making, ie tack on windshifts, what to do if stuck head to wind

6
APMrover2/system.cpp

@ -113,7 +113,7 @@ void Rover::init_ardupilot()
ins.set_log_raw_bit(MASK_LOG_IMU_RAW); 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 init_rc_in(); // sets up rc channels deadzone
g2.motors.init(); // init motors including setting servo out channels ranges g2.motors.init(); // init motors including setting servo out channels ranges
SRV_Channels::enable_aux_servos(); SRV_Channels::enable_aux_servos();
@ -271,7 +271,7 @@ void Rover::startup_INS_ground(void)
hal.scheduler->delay(100); hal.scheduler->delay(100);
ahrs.init(); 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_fly_forward(true);
ahrs.set_vehicle_class(AHRS_VEHICLE_GROUND); 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) uint8_t Rover::check_digital_pin(uint8_t pin)
{ {

Loading…
Cancel
Save