mirror of https://github.com/ArduPilot/ardupilot
AP_Motors_Heli: remove unused allow_arming check
This commit is contained in:
parent
b49fda4a94
commit
ca942f39dd
|
@ -98,9 +98,6 @@ public:
|
||||||
// heli specific methods
|
// heli specific methods
|
||||||
//
|
//
|
||||||
|
|
||||||
// allow_arming - returns true if main rotor is spinning and it is ok to arm
|
|
||||||
virtual bool allow_arming() const = 0;
|
|
||||||
|
|
||||||
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
||||||
bool parameter_check(bool display_msg) const;
|
bool parameter_check(bool display_msg) const;
|
||||||
|
|
||||||
|
|
|
@ -208,18 +208,6 @@ void AP_MotorsHeli_Single::output_test(uint8_t motor_seq, int16_t pwm)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// allow_arming - check if it's safe to arm
|
|
||||||
bool AP_MotorsHeli_Single::allow_arming() const
|
|
||||||
{
|
|
||||||
// returns false if main rotor speed is not zero
|
|
||||||
if (_main_rotor.get_rotor_speed() > 0) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// all other cases it is OK to arm
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
// set_desired_rotor_speed
|
// set_desired_rotor_speed
|
||||||
void AP_MotorsHeli_Single::set_desired_rotor_speed(int16_t desired_speed)
|
void AP_MotorsHeli_Single::set_desired_rotor_speed(int16_t desired_speed)
|
||||||
{
|
{
|
||||||
|
|
|
@ -80,9 +80,6 @@ public:
|
||||||
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
||||||
void output_test(uint8_t motor_seq, int16_t pwm);
|
void output_test(uint8_t motor_seq, int16_t pwm);
|
||||||
|
|
||||||
// allow_arming - returns true if main rotor is spinning and it is ok to arm
|
|
||||||
bool allow_arming() const;
|
|
||||||
|
|
||||||
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
|
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
|
||||||
void set_desired_rotor_speed(int16_t desired_speed);
|
void set_desired_rotor_speed(int16_t desired_speed);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue