diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index fa49e9d04a..881b86e11c 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -863,7 +863,6 @@ private: void update_heli_control_dynamics(void); void heli_update_landing_swash(); void heli_update_rotor_speed_targets(); - void heli_radio_passthrough(); bool heli_acro_init(bool ignore_checks); void heli_acro_run(); bool heli_stabilize_init(bool ignore_checks); diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 16451037ea..6e91a3af4a 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -266,9 +266,6 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) input_manager.set_stab_col_ramp(0.0); } } - - // reset RC Passthrough to motors - motors.reset_radio_passthrough(); #endif //HELI_FRAME } diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index 644bf2f833..c8eed908c2 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -193,10 +193,4 @@ void Copter::heli_update_rotor_speed_targets() rotor_runup_complete_last = motors.rotor_runup_complete(); } -// heli_radio_passthrough send RC inputs direct into motors library for use during manual passthrough for helicopter setup -void Copter::heli_radio_passthrough() -{ - motors.set_radio_passthrough(channel_roll->control_in/1000.0f, channel_pitch->control_in/1000.0f, channel_throttle->control_in/1000.0f, channel_yaw->control_in/1000.0f); -} - #endif // FRAME_CONFIG == HELI_FRAME diff --git a/ArduCopter/heli_control_acro.cpp b/ArduCopter/heli_control_acro.cpp index 535c7bdf73..4f8c3eb395 100644 --- a/ArduCopter/heli_control_acro.cpp +++ b/ArduCopter/heli_control_acro.cpp @@ -47,9 +47,6 @@ void Copter::heli_acro_run() } } - // send RC inputs direct into motors library for use during manual passthrough for helicopter setup - heli_radio_passthrough(); - if (!motors.has_flybar()){ // convert the input to the desired body frame rate get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw); diff --git a/ArduCopter/heli_control_stabilize.cpp b/ArduCopter/heli_control_stabilize.cpp index 9936036512..e646b2ca2d 100644 --- a/ArduCopter/heli_control_stabilize.cpp +++ b/ArduCopter/heli_control_stabilize.cpp @@ -46,9 +46,6 @@ void Copter::heli_stabilize_run() } } - // send RC inputs direct into motors library for use during manual passthrough for helicopter setup - heli_radio_passthrough(); - // apply SIMPLE mode transform to pilot inputs update_simple_mode();