mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_MotorsHeli: Change servo manual #defines into enum
This commit is contained in:
parent
d11e5d4ae4
commit
739d87a15b
@ -63,7 +63,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Description: Manual servo override for swash set-up. Do not set this manually!
|
// @Description: Manual servo override for swash set-up. Do not set this manually!
|
||||||
// @Values: 0:Disabled,1:Passthrough,2:Center
|
// @Values: 0:Disabled,1:Passthrough,2:Center
|
||||||
// @User: Standard
|
// @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
|
// @Param: GOV_SETPOINT
|
||||||
// @DisplayName: External Motor Governor Setpoint
|
// @DisplayName: External Motor Governor Setpoint
|
||||||
@ -161,7 +161,7 @@ void AP_MotorsHeli::Init()
|
|||||||
set_update_rate(_speed_hz);
|
set_update_rate(_speed_hz);
|
||||||
|
|
||||||
// ensure inputs are not passed through to servos on start-up
|
// 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
|
// initialise Servo/PWM ranges and endpoints
|
||||||
init_outputs();
|
init_outputs();
|
||||||
@ -208,7 +208,7 @@ void AP_MotorsHeli::output()
|
|||||||
void AP_MotorsHeli::output_armed_stabilizing()
|
void AP_MotorsHeli::output_armed_stabilizing()
|
||||||
{
|
{
|
||||||
// if manual override active after arming, deactivate it and reinitialize servos
|
// 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();
|
reset_flight_controls();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -220,7 +220,7 @@ void AP_MotorsHeli::output_armed_stabilizing()
|
|||||||
void AP_MotorsHeli::output_armed_not_stabilizing()
|
void AP_MotorsHeli::output_armed_not_stabilizing()
|
||||||
{
|
{
|
||||||
// if manual override active after arming, deactivate it and reinitialize servos
|
// 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();
|
reset_flight_controls();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -234,7 +234,7 @@ void AP_MotorsHeli::output_armed_not_stabilizing()
|
|||||||
void AP_MotorsHeli::output_armed_zero_throttle()
|
void AP_MotorsHeli::output_armed_zero_throttle()
|
||||||
{
|
{
|
||||||
// if manual override active after arming, deactivate it and reinitialize servos
|
// 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();
|
reset_flight_controls();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -247,13 +247,13 @@ void AP_MotorsHeli::output_armed_zero_throttle()
|
|||||||
void AP_MotorsHeli::output_disarmed()
|
void AP_MotorsHeli::output_disarmed()
|
||||||
{
|
{
|
||||||
// if manual override (i.e. when setting up swash)
|
// 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
|
// pass pilot commands straight through to swash
|
||||||
_roll_control_input = _roll_radio_passthrough;
|
_roll_control_input = _roll_radio_passthrough;
|
||||||
_pitch_control_input = _pitch_radio_passthrough;
|
_pitch_control_input = _pitch_radio_passthrough;
|
||||||
_throttle_control_input = _throttle_radio_passthrough;
|
_throttle_control_input = _throttle_radio_passthrough;
|
||||||
_yaw_control_input = _yaw_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
|
// center and fixate the swash
|
||||||
_roll_control_input = 0;
|
_roll_control_input = 0;
|
||||||
_pitch_control_input = 0;
|
_pitch_control_input = 0;
|
||||||
@ -341,7 +341,7 @@ void AP_MotorsHeli::reset_radio_passthrough()
|
|||||||
void AP_MotorsHeli::reset_flight_controls()
|
void AP_MotorsHeli::reset_flight_controls()
|
||||||
{
|
{
|
||||||
reset_radio_passthrough();
|
reset_radio_passthrough();
|
||||||
_servo_manual = AP_MOTORS_HELI_MANUAL_OFF;
|
_servo_mode = SERVO_CONTROL_MODE_AUTOMATED;
|
||||||
init_outputs();
|
init_outputs();
|
||||||
calculate_scalars();
|
calculate_scalars();
|
||||||
}
|
}
|
||||||
|
@ -60,11 +60,6 @@
|
|||||||
#define AP_MOTORS_HELI_NOFLYBAR 0
|
#define AP_MOTORS_HELI_NOFLYBAR 0
|
||||||
#define AP_MOTORS_HELI_FLYBAR 1
|
#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_HeliControls;
|
||||||
|
|
||||||
/// @class AP_MotorsHeli
|
/// @class AP_MotorsHeli
|
||||||
@ -170,6 +165,13 @@ public:
|
|||||||
// output - sends commands to the motors
|
// output - sends commands to the motors
|
||||||
void output();
|
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
|
// supports_yaw_passthrough
|
||||||
virtual bool supports_yaw_passthrough() const { return false; }
|
virtual bool supports_yaw_passthrough() const { return false; }
|
||||||
|
|
||||||
@ -213,7 +215,7 @@ protected:
|
|||||||
AP_Int16 _collective_min; // Lowest possible servo position for the swashplate
|
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_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_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_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_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
|
AP_Int8 _rsc_ramp_time; // Time in seconds for the output to the main rotor's ESC to reach full speed
|
||||||
|
@ -397,7 +397,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;
|
coll_out_scaled = _collective_out * _collective_scalar + _collective_min - 1000;
|
||||||
|
|
||||||
// if servo output not in manual mode, process pre-compensation factors
|
// 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
|
// 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
|
// 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
|
// also not required if we are using external gyro
|
||||||
|
Loading…
Reference in New Issue
Block a user