Browse Source

Rover: remove rc out initialisation wrappers

mission-4.1.18
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
9105284a7d
  1. 10
      APMrover2/APMrover2.cpp
  2. 2
      APMrover2/Rover.h
  3. 6
      APMrover2/radio.cpp
  4. 2
      APMrover2/system.cpp

10
APMrover2/APMrover2.cpp

@ -257,14 +257,6 @@ void Rover::update_logging2(void) @@ -257,14 +257,6 @@ void Rover::update_logging2(void)
}
/*
update aux servo mappings
*/
void Rover::update_aux(void)
{
SRV_Channels::enable_aux_servos();
}
/*
once a second events
*/
@ -279,7 +271,7 @@ void Rover::one_second_loop(void) @@ -279,7 +271,7 @@ void Rover::one_second_loop(void)
set_control_channels();
// cope with changes to aux functions
update_aux();
SRV_Channels::enable_aux_servos();
// update notify flags
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);

2
APMrover2/Rover.h

@ -391,7 +391,6 @@ private: @@ -391,7 +391,6 @@ private:
void update_compass(void);
void update_logging1(void);
void update_logging2(void);
void update_aux(void);
void one_second_loop(void);
void update_GPS(void);
void update_current_mode(void);
@ -474,7 +473,6 @@ private: @@ -474,7 +473,6 @@ private:
// radio.cpp
void set_control_channels(void);
void init_rc_in();
void init_rc_out();
void rudder_arm_disarm_check();
void read_radio();
void radio_failsafe_check(uint16_t pwm);

6
APMrover2/radio.cpp

@ -36,12 +36,6 @@ void Rover::init_rc_in() @@ -36,12 +36,6 @@ void Rover::init_rc_in()
channel_lateral->set_default_dead_zone(30);
}
void Rover::init_rc_out()
{
// set auxiliary ranges
update_aux();
}
/*
check for driver input on rudder/steering stick for arming/disarming
*/

2
APMrover2/system.cpp

@ -126,7 +126,7 @@ void Rover::init_ardupilot() @@ -126,7 +126,7 @@ void Rover::init_ardupilot()
set_control_channels(); // setup radio channels and ouputs ranges
init_rc_in(); // sets up rc channels deadzone
g2.motors.init(); // init motors including setting servo out channels ranges
init_rc_out(); // enable output
SRV_Channels::enable_aux_servos();
// init wheel encoders
g2.wheel_encoder.init();

Loading…
Cancel
Save