mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_MotorsHeli: Add parameter checks to Single class
This commit is contained in:
parent
818a5d103f
commit
2c612e5f8e
@ -107,7 +107,7 @@ public:
|
|||||||
virtual bool allow_arming() const = 0;
|
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() const;
|
virtual bool parameter_check() const;
|
||||||
|
|
||||||
// has_flybar - returns true if we have a mechical flybar
|
// has_flybar - returns true if we have a mechical flybar
|
||||||
virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
|
virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
|
||||||
|
@ -518,3 +518,20 @@ void AP_MotorsHeli_Single::servo_test()
|
|||||||
_pitch_control_input = _pitch_test;
|
_pitch_control_input = _pitch_test;
|
||||||
_yaw_control_input = _yaw_test;
|
_yaw_control_input = _yaw_test;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// parameter_check - check if helicopter specific parameters are sensible
|
||||||
|
bool AP_MotorsHeli_Single::parameter_check() const
|
||||||
|
{
|
||||||
|
// returns false if Phase Angle is outside of range
|
||||||
|
if ((_phase_angle > 90) || (_phase_angle < -90)){
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// returns false if External Gyro Gain is outside of range
|
||||||
|
if ((_ext_gyro_gain < 0) || (_ext_gyro_gain > 1000)){
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// check parent class parameters
|
||||||
|
return AP_MotorsHeli::parameter_check();
|
||||||
|
}
|
||||||
|
@ -83,6 +83,9 @@ public:
|
|||||||
// allow_arming - returns true if main rotor is spinning and it is ok to arm
|
// allow_arming - returns true if main rotor is spinning and it is ok to arm
|
||||||
bool allow_arming() const;
|
bool allow_arming() const;
|
||||||
|
|
||||||
|
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
||||||
|
bool parameter_check() 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
Block a user