5 #ifndef __AP_MOTORS_HELI_DUAL_H__ 6 #define __AP_MOTORS_HELI_DUAL_H__ 16 #define AP_MOTORS_HELI_DUAL_SERVO1_POS -60 17 #define AP_MOTORS_HELI_DUAL_SERVO2_POS 60 18 #define AP_MOTORS_HELI_DUAL_SERVO3_POS 180 19 #define AP_MOTORS_HELI_DUAL_SERVO4_POS -60 20 #define AP_MOTORS_HELI_DUAL_SERVO5_POS 60 21 #define AP_MOTORS_HELI_DUAL_SERVO6_POS 180 24 #define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_NORMAL 0 25 #define AP_MOTORS_HELI_DUAL_COLLECTIVE_DIRECTION_REVERSED 1 28 #define AP_MOTORS_HELI_DUAL_RSC CH_8 31 #define AP_MOTORS_HELI_DUAL_MODE_TANDEM 0 // tandem mode (rotors front and aft) 32 #define AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE 1 // transverse mode (rotors side by side) 35 #define AP_MOTORS_HELI_DUAL_DCP_SCALER 0.25f 38 #define AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS 6 41 #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN 1250 42 #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX 1750 43 #define AP_MOTORS_HELI_DUAL_COLLECTIVE2_MID 1500 109 void move_actuators(
float roll_out,
float pitch_out,
float coll_in,
float yaw_out)
override;
154 #endif // AP_MotorsHeli_Dual
AP_Int16 _collective2_max
#define AP_MOTORS_HELI_NOFLYBAR
float _rollFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
float get_main_rotor_speed() const override
#define AP_MOTORS_HELI_DUAL_RSC
void calculate_armed_scalars() override
float _collective2_mid_pct
void set_update_rate(uint16_t speed_hz) override
SRV_Channel * _swash_servo_4
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
void calculate_roll_pitch_collective_factors() override
AP_Int16 _collective2_mid
bool rotor_speed_above_critical() const override
void servo_test() override
bool has_flybar() const override
float _collectiveFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
static const struct AP_Param::GroupInfo var_info[]
SRV_Channel * _swash_servo_1
SRV_Channel * _swash_servo_3
void update_motor_control(RotorControlState state) override
RC_Channel manager, with EEPROM-backed storage of constants.
float _pitchFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
AP_Int16 _swash1_phase_angle
AP_Int16 _collective2_min
AP_Int16 _swash2_phase_angle
float get_rotor_speed() const
AP_Int8 _collective_direction
float _servo_test_cycle_time
AP_MotorsHeli_Dual(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_HELI_SPEED_DEFAULT)
#define AP_MOTORS_HELI_SPEED_DEFAULT
bool supports_yaw_passthrough() const override
float get_critical_speed() const
Common definitions and utility routines for the ArduPilot libraries.
float _yawFactor[AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS]
SRV_Channel * _swash_servo_5
#define AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS
Motor control class for Traditional Heli.
void output_test(uint8_t motor_seq, int16_t pwm) override
uint16_t get_motor_mask() override
SRV_Channel * _swash_servo_2
bool init_outputs() override
void set_desired_rotor_speed(float desired_speed) override
float get_desired_rotor_speed() const override
SRV_Channel * _swash_servo_6
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
void calculate_scalars() override