Browse Source

Copter: remove heli_radio_passthrough

Replaced with set_radio_passthrough which can be used for all frames
master
Randy Mackay 9 years ago
parent
commit
d2a42a7a0e
  1. 1
      ArduCopter/Copter.h
  2. 3
      ArduCopter/flight_mode.cpp
  3. 6
      ArduCopter/heli.cpp
  4. 3
      ArduCopter/heli_control_acro.cpp
  5. 3
      ArduCopter/heli_control_stabilize.cpp

1
ArduCopter/Copter.h

@ -863,7 +863,6 @@ private: @@ -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);

3
ArduCopter/flight_mode.cpp

@ -266,9 +266,6 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) @@ -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
}

6
ArduCopter/heli.cpp

@ -193,10 +193,4 @@ void Copter::heli_update_rotor_speed_targets() @@ -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

3
ArduCopter/heli_control_acro.cpp

@ -47,9 +47,6 @@ void Copter::heli_acro_run() @@ -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);

3
ArduCopter/heli_control_stabilize.cpp

@ -46,9 +46,6 @@ void Copter::heli_stabilize_run() @@ -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();

Loading…
Cancel
Save