AP_MotorsHeli: Change servo manual #defines into enum
This commit is contained in:
parent
750728fa1e
commit
22729e6927
@ -64,7 +64,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
// @Description: Manual servo override for swash set-up. Do not set this manually!
|
||||
// @Values: 0:Disabled,1:Passthrough,2:Center
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SV_MAN", 6, AP_MotorsHeli, _servo_manual, AP_MOTORS_HELI_MANUAL_OFF),
|
||||
AP_GROUPINFO("SV_MAN", 6, AP_MotorsHeli, _servo_mode, SERVO_CONTROL_MODE_AUTOMATED),
|
||||
|
||||
// @Param: GOV_SETPOINT
|
||||
// @DisplayName: External Motor Governor Setpoint
|
||||
@ -162,7 +162,7 @@ void AP_MotorsHeli::Init()
|
||||
set_update_rate(_speed_hz);
|
||||
|
||||
// ensure inputs are not passed through to servos on start-up
|
||||
_servo_manual = AP_MOTORS_HELI_MANUAL_OFF;
|
||||
_servo_mode = SERVO_CONTROL_MODE_AUTOMATED;
|
||||
|
||||
// initialise Servo/PWM ranges and endpoints
|
||||
init_outputs();
|
||||
@ -209,7 +209,7 @@ void AP_MotorsHeli::output()
|
||||
void AP_MotorsHeli::output_armed_stabilizing()
|
||||
{
|
||||
// if manual override active after arming, deactivate it and reinitialize servos
|
||||
if (_servo_manual != AP_MOTORS_HELI_MANUAL_OFF) {
|
||||
if (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED) {
|
||||
reset_flight_controls();
|
||||
}
|
||||
|
||||
@ -221,7 +221,7 @@ void AP_MotorsHeli::output_armed_stabilizing()
|
||||
void AP_MotorsHeli::output_armed_not_stabilizing()
|
||||
{
|
||||
// if manual override active after arming, deactivate it and reinitialize servos
|
||||
if (_servo_manual != AP_MOTORS_HELI_MANUAL_OFF) {
|
||||
if (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED) {
|
||||
reset_flight_controls();
|
||||
}
|
||||
|
||||
@ -235,7 +235,7 @@ void AP_MotorsHeli::output_armed_not_stabilizing()
|
||||
void AP_MotorsHeli::output_armed_zero_throttle()
|
||||
{
|
||||
// if manual override active after arming, deactivate it and reinitialize servos
|
||||
if (_servo_manual != AP_MOTORS_HELI_MANUAL_OFF) {
|
||||
if (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED) {
|
||||
reset_flight_controls();
|
||||
}
|
||||
|
||||
@ -248,13 +248,13 @@ void AP_MotorsHeli::output_armed_zero_throttle()
|
||||
void AP_MotorsHeli::output_disarmed()
|
||||
{
|
||||
// if manual override (i.e. when setting up swash)
|
||||
if (_servo_manual == AP_MOTORS_HELI_MANUAL_PASSTHROUGH) {
|
||||
if (_servo_mode == SERVO_CONTROL_MODE_MANUAL_PASSTHROUGH) {
|
||||
// pass pilot commands straight through to swash
|
||||
_roll_control_input = _roll_radio_passthrough;
|
||||
_pitch_control_input = _pitch_radio_passthrough;
|
||||
_throttle_control_input = _throttle_radio_passthrough;
|
||||
_yaw_control_input = _yaw_radio_passthrough;
|
||||
} else if (_servo_manual == AP_MOTORS_HELI_MANUAL_CENTER) {
|
||||
} else if (_servo_mode == SERVO_CONTROL_MODE_MANUAL_CENTER) {
|
||||
// center and fixate the swash
|
||||
_roll_control_input = 0;
|
||||
_pitch_control_input = 0;
|
||||
@ -354,7 +354,7 @@ void AP_MotorsHeli::reset_radio_passthrough()
|
||||
void AP_MotorsHeli::reset_flight_controls()
|
||||
{
|
||||
reset_radio_passthrough();
|
||||
_servo_manual = AP_MOTORS_HELI_MANUAL_OFF;
|
||||
_servo_mode = SERVO_CONTROL_MODE_AUTOMATED;
|
||||
init_outputs();
|
||||
calculate_scalars();
|
||||
}
|
||||
|
@ -54,11 +54,6 @@
|
||||
#define AP_MOTORS_HELI_NOFLYBAR 0
|
||||
#define AP_MOTORS_HELI_FLYBAR 1
|
||||
|
||||
// manual servo modes (used for setup)
|
||||
#define AP_MOTORS_HELI_MANUAL_OFF 0
|
||||
#define AP_MOTORS_HELI_MANUAL_PASSTHROUGH 1
|
||||
#define AP_MOTORS_HELI_MANUAL_CENTER 2
|
||||
|
||||
class AP_HeliControls;
|
||||
|
||||
/// @class AP_MotorsHeli
|
||||
@ -161,6 +156,13 @@ public:
|
||||
// output - sends commands to the motors
|
||||
void output();
|
||||
|
||||
// manual servo modes (used for setup)
|
||||
enum ServoControlModes {
|
||||
SERVO_CONTROL_MODE_AUTOMATED,
|
||||
SERVO_CONTROL_MODE_MANUAL_PASSTHROUGH,
|
||||
SERVO_CONTROL_MODE_MANUAL_CENTER,
|
||||
};
|
||||
|
||||
// supports_yaw_passthrough
|
||||
virtual bool supports_yaw_passthrough() const { return false; }
|
||||
|
||||
@ -204,7 +206,7 @@ protected:
|
||||
AP_Int16 _collective_min; // Lowest possible servo position for the swashplate
|
||||
AP_Int16 _collective_max; // Highest possible servo position for the swashplate
|
||||
AP_Int16 _collective_mid; // Swash servo position corresponding to zero collective pitch (or zero lift for Assymetrical blades)
|
||||
AP_Int8 _servo_manual; // Pass radio inputs directly to servos during set-up through mission planner
|
||||
AP_Int8 _servo_mode; // Pass radio inputs directly to servos during set-up through mission planner
|
||||
AP_Int16 _rsc_setpoint; // rotor speed when RSC mode is set to is enabledv
|
||||
AP_Int8 _rsc_mode; // Which main rotor ESC control mode is active
|
||||
AP_Int8 _rsc_ramp_time; // Time in seconds for the output to the main rotor's ESC to reach full speed
|
||||
|
@ -398,7 +398,7 @@ void AP_MotorsHeli_Single::move_actuators(int16_t roll_out, int16_t pitch_out, i
|
||||
coll_out_scaled = _collective_out * _collective_scalar + _collective_min - 1000;
|
||||
|
||||
// if servo output not in manual mode, process pre-compensation factors
|
||||
if (_servo_manual == 0) {
|
||||
if (_servo_mode == SERVO_CONTROL_MODE_AUTOMATED) {
|
||||
// rudder feed forward based on collective
|
||||
// the feed-forward is not required when the motor is stopped or at idle, and thus not creating torque
|
||||
// also not required if we are using external gyro
|
||||
|
Loading…
Reference in New Issue
Block a user