103 for (uint8_t i = 0; i < 5; i++) {
142 const float cos45 = cosf(
radians(45));
145 bool clockwise = x_clockwise[i];
148 clockwise = !clockwise;
204 float collective_out = collective_in;
205 if (collective_out <= 0.0
f) {
206 collective_out = 0.0f;
209 if (collective_out >= 1.0
f) {
210 collective_out = 1.0f;
223 collective_out = 1 - collective_out;
230 collective_out = collective_out*2-1;
233 collective_out *= collective_range;
251 if (out[i] * (out[i] + y) < 0) {
256 float s = -(out[i] / y);
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel)
uint16_t get_motor_mask() override
static const float angles[]
void output_test(uint8_t motor_seq, int16_t pwm) override
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
motor_frame_type _frame_type
void set_update_rate(uint16_t speed_hz) override
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define AP_MOTORS_HELI_COLLECTIVE_MIN
engine kill switch, used for gas airplanes and helicopters
float _collective_mid_pct
void set_desired_speed(float desired_speed)
struct AP_Motors::AP_Motors_flags _flags
struct AP_Motors::AP_Motors_limit limit
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
void update_motor_control(RotorControlState state) override
struct AP_MotorsHeli::heliflags_type _heliflags
float _rollFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void calculate_scalars() override
void set_idle_output(float idle_output)
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
bool is_runup_complete() const
AP_Int16 _rsc_idle_output
void calculate_roll_pitch_collective_factors() override
void set_throttle_curve(float thrcrv[5], uint16_t slewrate)
void set_control_mode(RotorControlMode mode)
int16_t calc_pwm_output_1to1(float input, const SRV_Channel *servo)
float _pitchFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
bool init_outputs() override
float _yawFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void output(RotorControlState state)
virtual void rc_write(uint8_t chan, uint16_t pwm)
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
void set_runup_time(int8_t runup_time)
#define AP_MOTORS_HELI_QUAD_RSC
#define AP_NESTEDGROUPINFO(clazz, idx)
static constexpr float radians(float deg)
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
uint8_t landing_collective
AP_Int16 _land_collective_min
void set_desired_rotor_speed(float desired_speed) override
void calculate_armed_scalars() override
float _collectiveFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void set_ramp_time(int8_t ramp_time)
Motor control class collective pitch quad helicopter (such as stingray)
uint8_t rotor_runup_complete
void set_collective(float collective)
void servo_test() override
SRV_Channel * _servo[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
#define AP_MOTORS_HELI_QUAD_NUM_MOTORS
static const struct AP_Param::GroupInfo var_info[]