mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsHeli: remove reset_radio_passthrough
This commit is contained in:
parent
b5593431bf
commit
4f1e62d551
|
@ -175,6 +175,9 @@ void AP_MotorsHeli::Init()
|
|||
// ensure inputs are not passed through to servos on start-up
|
||||
_servo_mode = SERVO_CONTROL_MODE_AUTOMATED;
|
||||
|
||||
// initialise radio passthrough for collective to middle
|
||||
_throttle_radio_passthrough = 0.5f;
|
||||
|
||||
// initialise Servo/PWM ranges and endpoints
|
||||
init_outputs();
|
||||
|
||||
|
@ -355,19 +358,9 @@ void AP_MotorsHeli::update_throttle_filter()
|
|||
_throttle_filter.apply(_throttle_in, 1.0f/_loop_rate);
|
||||
}
|
||||
|
||||
// reset_radio_passthrough used to reset all radio inputs to center
|
||||
void AP_MotorsHeli::reset_radio_passthrough()
|
||||
{
|
||||
_roll_radio_passthrough = 0.0f;
|
||||
_pitch_radio_passthrough = 0.0f;
|
||||
_throttle_radio_passthrough = 0.5f;
|
||||
_yaw_radio_passthrough = 0.0f;
|
||||
}
|
||||
|
||||
// reset_flight_controls - resets all controls and scalars to flight status
|
||||
void AP_MotorsHeli::reset_flight_controls()
|
||||
{
|
||||
reset_radio_passthrough();
|
||||
_servo_mode = SERVO_CONTROL_MODE_AUTOMATED;
|
||||
init_outputs();
|
||||
calculate_scalars();
|
||||
|
|
|
@ -128,9 +128,6 @@ public:
|
|||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||
virtual uint16_t get_motor_mask() = 0;
|
||||
|
||||
// reset_radio_passthrough used to reset all radio inputs to center
|
||||
void reset_radio_passthrough();
|
||||
|
||||
// servo_test - move servos through full range of movement
|
||||
// to be overloaded by child classes, different vehicle types would have different movement patterns
|
||||
virtual void servo_test() = 0;
|
||||
|
|
Loading…
Reference in New Issue