14 #define AP_MOTORS_HELI_QUAD_RSC CH_8 17 #define AP_MOTORS_HELI_QUAD_COLLECTIVE_MIN 1100 18 #define AP_MOTORS_HELI_QUAD_COLLECTIVE_MAX 1900 20 #define AP_MOTORS_HELI_QUAD_NUM_MOTORS 4 84 void move_actuators(
float roll_out,
float pitch_out,
float coll_in,
float yaw_out)
override;
#define AP_MOTORS_HELI_NOFLYBAR
uint16_t get_motor_mask() override
void output_test(uint8_t motor_seq, int16_t pwm) override
void set_update_rate(uint16_t speed_hz) override
float get_desired_rotor_speed() const override
void update_motor_control(RotorControlState state) override
bool has_flybar() const override
float _rollFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void calculate_scalars() override
void calculate_roll_pitch_collective_factors() override
RC_Channel manager, with EEPROM-backed storage of constants.
float _pitchFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
float get_main_rotor_speed() const override
float get_rotor_speed() const
bool init_outputs() override
float _yawFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
#define AP_MOTORS_HELI_SPEED_DEFAULT
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
float get_critical_speed() const
Common definitions and utility routines for the ArduPilot libraries.
#define AP_MOTORS_HELI_QUAD_RSC
bool supports_yaw_passthrough() const override
Motor control class for Traditional Heli.
void set_desired_rotor_speed(float desired_speed) override
bool rotor_speed_above_critical() const override
void calculate_armed_scalars() override
float _collectiveFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
AP_MotorsHeli_Quad(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_HELI_SPEED_DEFAULT)
void servo_test() override
SRV_Channel * _servo[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
#define AP_MOTORS_HELI_QUAD_NUM_MOTORS
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
static const struct AP_Param::GroupInfo var_info[]