12 #define AP_MOTORS_HELI_SINGLE_RSC CH_8 13 #define AP_MOTORS_HELI_SINGLE_AUX CH_7 16 #define AP_MOTORS_HELI_SINGLE_SERVO1_POS -60 17 #define AP_MOTORS_HELI_SINGLE_SERVO2_POS 60 18 #define AP_MOTORS_HELI_SINGLE_SERVO3_POS 180 21 #define AP_MOTORS_HELI_SINGLE_SWASH_H3 0 22 #define AP_MOTORS_HELI_SINGLE_SWASH_H1 1 23 #define AP_MOTORS_HELI_SINGLE_SWASH_H3_140 2 26 #define AP_MOTORS_HELI_SINGLE_COLLECTIVE_DIRECTION_NORMAL 0 27 #define AP_MOTORS_HELI_SINGLE_COLLECTIVE_DIRECTION_REVERSED 1 30 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO 0 31 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO 1 32 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH 2 33 #define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH 3 36 #define AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT 500 39 #define AP_MOTORS_HELI_SINGLE_EXT_GYRO_GAIN 350 42 #define AP_MOTORS_HELI_SINGLE_COLYAW_RANGE 10.0f 45 #define AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS 3 119 void move_actuators(
float roll_out,
float pitch_out,
float coll_in,
float yaw_out)
override;
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO
void calculate_roll_pitch_collective_factors() override
#define AP_MOTORS_HELI_SINGLE_AUX
AP_MotorsHeli_RSC _main_rotor
float _rollFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
AP_Float _collective_yaw_effect
SRV_Channel * _swash_servo_2
bool init_outputs() override
bool rotor_speed_above_critical() const override
AP_Int16 _ext_gyro_gain_std
#define AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS
void set_desired_rotor_speed(float desired_speed) override
AP_Int16 _direct_drive_tailspeed
AP_Int16 _ext_gyro_gain_acro
void ext_gyro_gain(float gain) override
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
#define AP_MOTORS_HELI_SINGLE_RSC
AP_MotorsHeli_RSC _tail_rotor
SRV_Channel * _swash_servo_3
float get_desired_speed() const
float _pitchFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
float _collectiveFactor[AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS]
void servo_test() override
AP_MotorsHeli_Single(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_HELI_SPEED_DEFAULT)
void output_test(uint8_t motor_seq, int16_t pwm) override
float get_rotor_speed() const
void move_yaw(float yaw_out)
#define AP_MOTORS_HELI_SPEED_DEFAULT
bool has_flybar() const override
float get_critical_speed() const
bool parameter_check(bool display_msg) const override
Common definitions and utility routines for the ArduPilot libraries.
void write_aux(float servo_out)
bool supports_yaw_passthrough() const override
float _servo_test_cycle_time
static const struct AP_Param::GroupInfo var_info[]
void calculate_scalars() override
Motor control class for Traditional Heli.
uint16_t get_motor_mask() override
AP_Int8 _collective_direction
void set_update_rate(uint16_t speed_hz) override
SRV_Channel * _swash_servo_1
void calculate_armed_scalars() override
void set_acro_tail(bool set) override
void update_motor_control(RotorControlState state) override
float get_main_rotor_speed() const override
float get_desired_rotor_speed() const override
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)