10 #define AP_MOTORS_MOT_1 0U 11 #define AP_MOTORS_MOT_2 1U 12 #define AP_MOTORS_MOT_3 2U 13 #define AP_MOTORS_MOT_4 3U 14 #define AP_MOTORS_MOT_5 4U 15 #define AP_MOTORS_MOT_6 5U 16 #define AP_MOTORS_MOT_7 6U 17 #define AP_MOTORS_MOT_8 7U 18 #define AP_MOTORS_MOT_9 8U 19 #define AP_MOTORS_MOT_10 9U 20 #define AP_MOTORS_MOT_11 10U 21 #define AP_MOTORS_MOT_12 11U 23 #define AP_MOTORS_MAX_NUM_MOTORS 12 26 #define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors 134 virtual void output() = 0;
149 void set_radio_passthrough(
float roll_input,
float pitch_input,
float throttle_input,
float yaw_input);
169 virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz);
void set_air_density_ratio(float ratio)
virtual void rc_write_angle(uint8_t chan, int16_t angle_cd)
void set_throttle_filter_cutoff(float filt_hz)
bool initialised_ok() const
void set_throttle_avg_max(float throttle_avg_max)
void set_yaw(float yaw_in)
struct AP_Motors::AP_Motors_flags _flags
virtual void set_update_rate(uint16_t speed_hz)
struct AP_Motors::AP_Motors_limit limit
#define AP_MOTORS_SPEED_DEFAULT
enum spool_up_down_desired get_desired_spool_state(void) const
int16_t calc_pwm_output_0to1(float input, const SRV_Channel *servo)
void set_loop_rate(uint16_t loop_rate)
void set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input)
static AP_Motors * get_instance(void)
void set_cutoff_frequency(float cutoff_freq)
static AP_Motors * _instance
float get_lateral() const
float get_throttle_bidirectional() const
bool get_interlock() const
virtual void output_armed_stabilizing()=0
virtual void save_params_on_disarm()
virtual uint16_t get_motor_mask()=0
int16_t calc_pwm_output_1to1(float input, const SRV_Channel *servo)
pwm_type get_pwm_type(void) const
virtual float get_throttle_hover() const =0
virtual void output_min()=0
virtual void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)=0
void set_throttle(float throttle_in)
float get_forward() const
void set_forward(float forward_in)
float _throttle_radio_passthrough
virtual void rc_write(uint8_t chan, uint16_t pwm)
AP_Motors(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
float _pitch_radio_passthrough
LowPassFilterFloat _throttle_filter
Common definitions and utility routines for the ArduPilot libraries.
float constrain_float(const float amt, const float low, const float high)
void set_lateral(float lateral_in)
void add_motor_num(int8_t motor_num)
virtual void output_test(uint8_t motor_seq, int16_t pwm)=0
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
AP_HAL::AnalogSource * chan
float _roll_radio_passthrough
virtual void set_desired_spool_state(enum spool_up_down_desired spool)
spool_up_down_desired _spool_desired
float _yaw_radio_passthrough
void set_pitch(float pitch_in)
uint16_t _motor_fast_mask
void set_roll(float roll_in)
float get_throttle() const
virtual void init(motor_frame_class frame_class, motor_frame_type frame_type)=0
virtual void update_throttle_filter()=0
virtual uint32_t rc_map_mask(uint32_t mask) const
void set_interlock(bool set)