AP_Motors:TradHeli - DDVP Ramp/Runup

Change to ramp and runup DDVP tail rotor to prevent torque pitching the frame and provide runup in sync with main
rotor like a mechanically driven tail.

Fix some comments and remove indents found in whitespace in AP_MotorsHeli.cpp and AP_MotorsHeli.h
This commit is contained in:
ChristopherOlson 2018-03-08 11:16:31 -06:00 committed by Randy Mackay
parent 9208308121
commit 96793a3ae7
4 changed files with 22 additions and 24 deletions

View File

@ -129,7 +129,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
// @Increment: 10
// @User: Standard
AP_GROUPINFO("RSC_POWER_LOW", 14, AP_MotorsHeli, _rsc_power_low, AP_MOTORS_HELI_RSC_POWER_LOW_DEFAULT),
// @Param: RSC_POWER_HIGH
// @DisplayName: Throttle Servo High Power Position
// @Description: Throttle output at maximum collective pitch. This is on a scale from 0 to 1000, where 1000 is full throttle and 0 is zero throttle. Actual PWM values are controlled by H_RSC_PWM_MIN and H_RSC_PWM_MAX.
@ -170,7 +170,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
// @Increment: 10
// @User: Standard
AP_GROUPINFO("RSC_SLEWRATE", 19, AP_MotorsHeli, _rsc_slewrate, 0),
AP_GROUPEND
};
@ -183,7 +183,7 @@ void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_t
{
// remember frame type
_frame_type = frame_type;
// set update rate
set_update_rate(_speed_hz);

View File

@ -91,7 +91,7 @@ public:
// set_inverted_flight - enables/disables inverted flight
void set_inverted_flight(bool inverted) { _heliflags.inverted_flight = inverted; }
// get_rsc_mode - gets the rotor speed control method (AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH or AP_MOTORS_HELI_RSC_MODE_SETPOINT)
uint8_t get_rsc_mode() const { return _rsc_mode; }
@ -121,7 +121,7 @@ public:
// ext_gyro_gain - set external gyro gain in range 0 ~ 1
virtual void ext_gyro_gain(float gain) {}
// output - sends commands to the motors
void output();
@ -196,7 +196,7 @@ protected:
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
AP_Int8 _rsc_ramp_time; // Time in seconds for the output to the main rotor's ESC to reach setpoint
AP_Int8 _rsc_runup_time; // Time in seconds for the main rotor to reach full speed. Must be longer than _rsc_ramp_time
AP_Int16 _land_collective_min; // Minimum collective when landed or landing
AP_Int16 _rsc_critical; // Rotor speed below which flight is not possible

View File

@ -23,7 +23,7 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
AP_NESTEDGROUPINFO(AP_MotorsHeli, 0),
// @Param: SV1_POS
// @DisplayName: Servo 1 Position
// @Description: Angular location of swash servo #1
@ -50,7 +50,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
// @User: Standard
// @Increment: 1
AP_GROUPINFO("SV3_POS", 3, AP_MotorsHeli_Single, _servo3_pos, AP_MOTORS_HELI_SINGLE_SERVO3_POS),
// @Param: TAIL_TYPE
// @DisplayName: Tail Type
// @Description: Tail type selection. Simpler yaw controller used if external gyro is selected
@ -97,7 +97,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
// @Values: 0:NoFlybar,1:Flybar
// @User: Standard
AP_GROUPINFO("FLYBAR_MODE", 9, AP_MotorsHeli_Single, _flybar_mode, AP_MOTORS_HELI_NOFLYBAR),
// @Param: TAIL_SPEED
// @DisplayName: Direct Drive VarPitch Tail ESC speed
// @Description: Direct Drive VarPitch Tail ESC speed in PWM microseconds. Only used when TailType is DirectDrive VarPitch
@ -105,7 +105,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
// @Units: PWM
// @Increment: 1
// @User: Standard
AP_GROUPINFO("TAIL_SPEED", 10, AP_MotorsHeli_Single, _direct_drive_tailspeed, AP_MOTORS_HELI_SINGLE_DDVPT_SPEED_DEFAULT),
AP_GROUPINFO("TAIL_SPEED", 10, AP_MotorsHeli_Single, _direct_drive_tailspeed, AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT),
// @Param: GYR_GAIN_ACRO
// @DisplayName: External Gyro Gain for ACRO
@ -222,7 +222,7 @@ void AP_MotorsHeli_Single::set_desired_rotor_speed(float desired_speed)
{
_main_rotor.set_desired_speed(desired_speed);
// always send desired speed to tail rotor control, will do nothing if not DDVPT not enabled
// always send desired speed to tail rotor control, will do nothing if not DDVP not enabled
_tail_rotor.set_desired_speed(_direct_drive_tailspeed/1000.0f);
}
@ -256,12 +256,12 @@ void AP_MotorsHeli_Single::calculate_scalars()
// send setpoints to main rotor controller and trigger recalculation of scalars
_main_rotor.set_control_mode(static_cast<RotorControlMode>(_rsc_mode.get()));
calculate_armed_scalars();
// send setpoints to tail rotor controller and trigger recalculation of scalars
// send setpoints to DDVP rotor controller and trigger recalculation of scalars
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
_tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_SPEED_SETPOINT);
_tail_rotor.set_ramp_time(AP_MOTORS_HELI_SINGLE_DDVPT_RAMP_TIME);
_tail_rotor.set_runup_time(AP_MOTORS_HELI_SINGLE_DDVPT_RUNUP_TIME);
_tail_rotor.set_ramp_time(_rsc_ramp_time);
_tail_rotor.set_runup_time(_rsc_runup_time);
_tail_rotor.set_critical_speed(_rsc_critical/1000.0f);
_tail_rotor.set_idle_output(_rsc_idle_output/1000.0f);
} else {
@ -360,7 +360,7 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
if (_heliflags.inverted_flight) {
coll_in = 1 - coll_in;
}
// rescale roll_out and pitch_out into the min and max ranges to provide linear motion
// across the input range instead of stopping when the input hits the constrain value
// these calculations are based on an assumption of the user specified cyclic_max
@ -432,7 +432,7 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
servo1_out = 2*servo1_out - 1;
servo2_out = 2*servo2_out - 1;
servo3_out = 2*servo3_out - 1;
// actually move the servos
rc_write(AP_MOTORS_MOT_1, calc_pwm_output_1to1(servo1_out, _swash_servo_1));
rc_write(AP_MOTORS_MOT_2, calc_pwm_output_1to1(servo2_out, _swash_servo_2));

View File

@ -27,10 +27,8 @@
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH 2
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH 3
// default direct-drive variable pitch tail defaults
#define AP_MOTORS_HELI_SINGLE_DDVPT_SPEED_DEFAULT 500
#define AP_MOTORS_HELI_SINGLE_DDVPT_RAMP_TIME 2
#define AP_MOTORS_HELI_SINGLE_DDVPT_RUNUP_TIME 3
// direct-drive variable pitch defaults
#define AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT 500
// default external gyro gain
#define AP_MOTORS_HELI_SINGLE_EXT_GYRO_GAIN 350
@ -79,7 +77,7 @@ public:
// calculate_armed_scalars - recalculates scalars that can change while armed
void calculate_armed_scalars() override;
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t get_motor_mask() override;
@ -97,7 +95,7 @@ public:
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
bool parameter_check(bool display_msg) const override;
// var_info
static const struct AP_Param::GroupInfo var_info[];
@ -154,7 +152,7 @@ protected:
SRV_Channel *_swash_servo_3;
SRV_Channel *_yaw_servo;
SRV_Channel *_servo_aux;
bool _acro_tail = false;
float _rollFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS];
float _pitchFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS];