271 for (uint8_t i = 0; i < 5; i++) {
447 collective_in = 1 - collective_in;
450 float yaw_compensation = 0.0f;
460 yaw_out = yaw_out + yaw_compensation;
474 float collective_out = collective_in;
475 if (collective_out <= 0.0
f) {
476 collective_out = 0.0f;
479 if (collective_out >= 1.0
f) {
480 collective_out = 1.0f;
485 float collective2_out = collective_out;
499 float collective_out_scaled = collective_out * collective_scaler + (
_collective_min - 1000)*0.001
f;
503 float collective2_out_scaled = collective2_out * collective2_scaler + (
_collective2_min - 1000)*0.001
f;
507 collective_out_scaled = 1 - collective_out_scaled;
508 collective2_out_scaled = 1 - collective2_out_scaled;
524 servo1_out = 2*servo1_out - 1;
525 servo2_out = 2*servo2_out - 1;
526 servo3_out = 2*servo3_out - 1;
527 servo4_out = 2*servo4_out - 1;
528 servo5_out = 2*servo5_out - 1;
529 servo6_out = 2*servo6_out - 1;
AP_Int16 _collective2_max
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define AP_MOTORS_HELI_DUAL_MODE_TANDEM
float _rollFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
#define AP_MOTORS_HELI_DUAL_RSC
#define AP_MOTORS_HELI_DUAL_DCP_SCALER
#define AP_MOTORS_HELI_COLLECTIVE_MIN
engine kill switch, used for gas airplanes and helicopters
void calculate_armed_scalars() override
float _collective2_mid_pct
float _collective_mid_pct
void set_update_rate(uint16_t speed_hz) override
void set_desired_speed(float desired_speed)
SRV_Channel * _swash_servo_4
struct AP_Motors::AP_Motors_flags _flags
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN
struct AP_Motors::AP_Motors_limit limit
void calculate_roll_pitch_collective_factors() override
AP_Int16 _collective2_mid
#define AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE
void set_critical_speed(float critical_speed)
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
#define AP_MOTORS_HELI_COLLECTIVE_MAX
int16_t calc_pwm_output_1to1_swash_servo(float input, const SRV_Channel *servo)
void servo_test() override
struct AP_MotorsHeli::heliflags_type _heliflags
#define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX
#define AP_MOTORS_HELI_DUAL_SERVO3_POS
#define AP_MOTORS_HELI_DUAL_SERVO1_POS
float _collectiveFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
void set_idle_output(float idle_output)
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
static const struct AP_Param::GroupInfo var_info[]
bool is_runup_complete() const
uint8_t _servo_test_cycle_counter
SRV_Channel * _swash_servo_1
SRV_Channel * _swash_servo_3
AP_Int16 _rsc_idle_output
void set_throttle_curve(float thrcrv[5], uint16_t slewrate)
void update_motor_control(RotorControlState state) override
float _pitchFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
these allow remapping of copter motors
void set_control_mode(RotorControlMode mode)
AP_Int16 _swash1_phase_angle
AP_Int16 _collective2_min
void reset_swash_servo(SRV_Channel *servo)
AP_Int16 _swash2_phase_angle
AP_Int8 _collective_direction
float _servo_test_cycle_time
#define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_REVERSED
void output(RotorControlState state)
virtual void rc_write(uint8_t chan, uint16_t pwm)
LowPassFilterFloat _throttle_filter
Motor control class for dual heli (tandem or transverse)
float _yawFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
#define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MID
void set_runup_time(int8_t runup_time)
#define AP_NESTEDGROUPINFO(clazz, idx)
static constexpr float radians(float deg)
SRV_Channel * _swash_servo_5
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
uint8_t landing_collective
#define AP_MOTORS_HELI_DUAL_SERVO5_POS
AP_Int16 _land_collective_min
void output_test(uint8_t motor_seq, int16_t pwm) override
uint16_t get_motor_mask() override
#define AP_MOTORS_HELI_DUAL_SERVO2_POS
SRV_Channel * _swash_servo_2
bool init_outputs() override
void set_desired_rotor_speed(float desired_speed) override
void set_ramp_time(int8_t ramp_time)
#define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_NORMAL
uint8_t rotor_runup_complete
#define AP_MOTORS_HELI_DUAL_SERVO6_POS
void set_collective(float collective)
#define AP_MOTORS_HELI_DUAL_SERVO4_POS
SRV_Channel * _swash_servo_6
void calculate_scalars() override