APM:Libraries
AP_Motors_Class.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
5 #include <AP_Notify/AP_Notify.h> // Notify library
7 #include <Filter/Filter.h> // filter library
8 
9 // offsets for motors in motor_out and _motor_filtered arrays
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
22 
23 #define AP_MOTORS_MAX_NUM_MOTORS 12
24 
25 // motor update rate
26 #define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
27 
29 class AP_Motors {
30 public:
31 
47  };
56  MOTOR_FRAME_TYPE_Y6F = 11 // for FireFlyY6
57  };
58 
59  // Constructor
60  AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
61 
62  // singleton support
63  static AP_Motors *get_instance(void) { return _instance; }
64 
65  // check initialisation succeeded
66  bool initialised_ok() const { return _flags.initialised_ok; }
67 
68  // arm, disarm or check status status of motors
69  bool armed() const { return _flags.armed; }
70  void armed(bool arm);
71 
72  // set motor interlock status
73  void set_interlock(bool set) { _flags.interlock = set;}
74 
75  // get motor interlock status. true means motors run, false motors don't run
76  bool get_interlock() const { return _flags.interlock; }
77 
78  // set_roll, set_pitch, set_yaw, set_throttle
79  void set_roll(float roll_in) { _roll_in = roll_in; }; // range -1 ~ +1
80  void set_pitch(float pitch_in) { _pitch_in = pitch_in; }; // range -1 ~ +1
81  void set_yaw(float yaw_in) { _yaw_in = yaw_in; }; // range -1 ~ +1
82  void set_throttle(float throttle_in) { _throttle_in = throttle_in; }; // range 0 ~ 1
83  void set_throttle_avg_max(float throttle_avg_max) { _throttle_avg_max = constrain_float(throttle_avg_max,0.0f,1.0f); }; // range 0 ~ 1
85  void set_forward(float forward_in) { _forward_in = forward_in; }; // range -1 ~ +1
86  void set_lateral(float lateral_in) { _lateral_in = lateral_in; }; // range -1 ~ +1
87 
88  // accessors for roll, pitch, yaw and throttle inputs to motors
89  float get_roll() const { return _roll_in; }
90  float get_pitch() const { return _pitch_in; }
91  float get_yaw() const { return _yaw_in; }
92  float get_throttle() const { return constrain_float(_throttle_filter.get(),0.0f,1.0f); }
93  float get_throttle_bidirectional() const { return constrain_float(2*(_throttle_filter.get()-0.5f),-1.0f,1.0f); }
94  float get_forward() const { return _forward_in; }
95  float get_lateral() const { return _lateral_in; }
96  virtual float get_throttle_hover() const = 0;
97 
98  // spool up states
100  DESIRED_SHUT_DOWN = 0, // all motors stop
101  DESIRED_SPIN_WHEN_ARMED = 1, // all motors at spin when armed
102  DESIRED_THROTTLE_UNLIMITED = 2, // motors are no longer constrained by start up procedure
103  };
104 
105  virtual void set_desired_spool_state(enum spool_up_down_desired spool) { _spool_desired = spool; };
106 
108 
109  // set_density_ratio - sets air density as a proportion of sea level density
110  void set_air_density_ratio(float ratio) { _air_density_ratio = ratio; }
111 
112  // structure for holding motor limit flags
114  uint8_t roll_pitch : 1; // we have reached roll or pitch limit
115  uint8_t yaw : 1; // we have reached yaw limit
116  uint8_t throttle_lower : 1; // we have reached throttle's lower limit
117  uint8_t throttle_upper : 1; // we have reached throttle's upper limit
118  } limit;
119 
120  //
121  // virtual functions that should be implemented by child classes
122  //
123 
124  // set update rate to motors - a value in hertz
125  virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; }
126 
127  // init
128  virtual void init(motor_frame_class frame_class, motor_frame_type frame_type) = 0;
129 
130  // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
131  virtual void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) = 0;
132 
133  // output - sends commands to the motors
134  virtual void output() = 0;
135 
136  // output_min - sends minimum values out to the motors
137  virtual void output_min() = 0;
138 
139  // output_test - spin a motor at the pwm value specified
140  // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
141  // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
142  virtual void output_test(uint8_t motor_seq, int16_t pwm) = 0;
143 
144  // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
145  // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
146  virtual uint16_t get_motor_mask() = 0;
147 
148  // pilot input in the -1 ~ +1 range for roll, pitch and yaw. 0~1 range for throttle
149  void set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input);
150 
151  // set loop rate. Used to support loop rate as a parameter
152  void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }
153 
162  pwm_type get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); }
163 
164 protected:
165  // output functions that should be overloaded by child classes
166  virtual void output_armed_stabilizing()=0;
167  virtual void rc_write(uint8_t chan, uint16_t pwm);
168  virtual void rc_write_angle(uint8_t chan, int16_t angle_cd);
169  virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz);
170  virtual uint32_t rc_map_mask(uint32_t mask) const;
171 
172  // add a motor to the motor map
173  void add_motor_num(int8_t motor_num);
174 
175  // update the throttle input filter
176  virtual void update_throttle_filter() = 0;
177 
178  // save parameters as part of disarming
179  virtual void save_params_on_disarm() {}
180 
181  // convert input in -1 to +1 range to pwm output
182  int16_t calc_pwm_output_1to1(float input, const SRV_Channel *servo);
183 
184  // convert input in 0 to +1 range to pwm output
185  int16_t calc_pwm_output_0to1(float input, const SRV_Channel *servo);
186 
187  // flag bitmask
189  uint8_t armed : 1; // 0 if disarmed, 1 if armed
190  uint8_t interlock : 1; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run)
191  uint8_t initialised_ok : 1; // 1 if initialisation was successful
192  } _flags;
193 
194  // internal variables
195  uint16_t _loop_rate; // rate in Hz at which output() function is called (normally 400hz)
196  uint16_t _speed_hz; // speed in hz to send updates to motors
197  float _roll_in; // desired roll control from attitude controllers, -1 ~ +1
198  float _pitch_in; // desired pitch control from attitude controller, -1 ~ +1
199  float _yaw_in; // desired yaw control from attitude controller, -1 ~ +1
200  float _throttle_in; // last throttle input from set_throttle caller
201  float _forward_in; // last forward input from set_forward caller
202  float _lateral_in; // last lateral input from set_lateral caller
203  float _throttle_avg_max; // last throttle input from set_throttle_avg_max
204  LowPassFilterFloat _throttle_filter; // throttle input filter
205  spool_up_down_desired _spool_desired; // desired spool state
206 
207  // air pressure compensation variables
208  float _air_density_ratio; // air density / sea level density - decreases in altitude
209 
210  // mask of what channels need fast output
212 
213  // pass through variables
214  float _roll_radio_passthrough; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
215  float _pitch_radio_passthrough; // pitch input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
216  float _throttle_radio_passthrough; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed
217  float _yaw_radio_passthrough; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
218 
219  AP_Int8 _pwm_type; // PWM output type
220 
221 private:
223 };
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)
float _forward_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
static uint16_t pwm
Definition: RCOutput.cpp:20
int16_t calc_pwm_output_0to1(float input, const SRV_Channel *servo)
void set_loop_rate(uint16_t loop_rate)
virtual void output()=0
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)
float _lateral_in
static AP_Motors * _instance
float get_lateral() const
float get_throttle_bidirectional() const
bool armed() const
bool get_interlock() const
virtual void output_armed_stabilizing()=0
virtual void save_params_on_disarm()
uint16_t _loop_rate
#define f(i)
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
uint16_t _speed_hz
virtual void output_min()=0
float get_roll() const
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_avg_max
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)
const T & get() const
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)
Definition: AP_Math.h:142
float get_yaw() const
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
Definition: AnalogIn.cpp:8
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)
float _air_density_ratio
uint16_t _motor_fast_mask
float get_pitch() const
void set_roll(float roll_in)
float get_throttle() const
virtual void init(motor_frame_class frame_class, motor_frame_type frame_type)=0
AP_Int8 _pwm_type
virtual void update_throttle_filter()=0
virtual uint32_t rc_map_mask(uint32_t mask) const
float _throttle_in
void set_interlock(bool set)