APM:Libraries
AP_Motors_Class.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_Motors.cpp - ArduCopter motors library
18  * Code by RandyMackay. DIYDrones.com
19  *
20  */
21 
22 #include "AP_Motors_Class.h"
23 #include <AP_HAL/AP_HAL.h>
25 #include <GCS_MAVLink/GCS.h>
26 
27 extern const AP_HAL::HAL& hal;
28 
29 // singleton instance
31 
32 // Constructor
33 AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
34  _loop_rate(loop_rate),
35  _speed_hz(speed_hz),
36  _roll_in(0.0f),
37  _pitch_in(0.0f),
38  _yaw_in(0.0f),
39  _throttle_in(0.0f),
40  _throttle_avg_max(0.0f),
41  _throttle_filter(),
42  _spool_desired(DESIRED_SHUT_DOWN),
43  _air_density_ratio(1.0f),
44  _motor_fast_mask(0)
45 {
46  _instance = this;
47 
48  // init other flags
49  _flags.armed = false;
50  _flags.interlock = false;
51  _flags.initialised_ok = false;
52 
53  // setup throttle filtering
56 
57  // init limit flags
58  limit.roll_pitch = true;
59  limit.yaw = true;
60  limit.throttle_lower = true;
61  limit.throttle_upper = true;
62 };
63 
64 void AP_Motors::armed(bool arm)
65 {
66  if (_flags.armed != arm) {
67  _flags.armed = arm;
68  AP_Notify::flags.armed = arm;
69  if (!arm) {
71  }
72  }
73 };
74 
75 // pilot input in the -1 ~ +1 range for roll, pitch and yaw. 0~1 range for throttle
76 void AP_Motors::set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input)
77 {
78  _roll_radio_passthrough = roll_input;
79  _pitch_radio_passthrough = pitch_input;
80  _throttle_radio_passthrough = throttle_input;
81  _yaw_radio_passthrough = yaw_input;
82 }
83 
84 /*
85  write to an output channel
86  */
87 void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
88 {
90  SRV_Channels::set_output_pwm(function, pwm);
91 }
92 
93 /*
94  write to an output channel for an angle actuator
95  */
96 void AP_Motors::rc_write_angle(uint8_t chan, int16_t angle_cd)
97 {
99  SRV_Channels::set_output_scaled(function, angle_cd);
100 }
101 
102 /*
103  set frequency of a set of channels
104  */
105 void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
106 {
107  if (freq_hz > 50) {
108  _motor_fast_mask |= mask;
109  }
110 
111  mask = rc_map_mask(mask);
112  hal.rcout->set_freq(mask, freq_hz);
113 
114  switch (pwm_type(_pwm_type.get())) {
115  case PWM_TYPE_ONESHOT:
116  if (freq_hz > 50 && mask != 0) {
118  }
119  break;
120  case PWM_TYPE_ONESHOT125:
121  if (freq_hz > 50 && mask != 0) {
123  }
124  break;
125  case PWM_TYPE_BRUSHED:
127  break;
128  case PWM_TYPE_DSHOT150:
130  break;
131  case PWM_TYPE_DSHOT300:
133  break;
134  case PWM_TYPE_DSHOT600:
136  break;
137  case PWM_TYPE_DSHOT1200:
139  break;
140  default:
142  break;
143  }
144 }
145 
146 /*
147  map an internal motor mask to real motor mask, accounting for
148  SERVOn_FUNCTION mappings, and allowing for multiple outputs per
149  motor number
150  */
151 uint32_t AP_Motors::rc_map_mask(uint32_t mask) const
152 {
153  uint32_t mask2 = 0;
154  for (uint8_t i=0; i<32; i++) {
155  uint32_t bit = 1UL<<i;
156  if (mask & bit) {
158  mask2 |= SRV_Channels::get_output_channel_mask(function);
159  }
160  }
161  return mask2;
162 }
163 
164 // convert input in -1 to +1 range to pwm output
165 int16_t AP_Motors::calc_pwm_output_1to1(float input, const SRV_Channel *servo)
166 {
167  int16_t ret;
168 
169  input = constrain_float(input, -1.0f, 1.0f);
170 
171  if (servo->get_reversed()) {
172  input = -input;
173  }
174 
175  if (input >= 0.0f) {
176  ret = ((input * (servo->get_output_max() - servo->get_trim())) + servo->get_trim());
177  } else {
178  ret = ((input * (servo->get_trim() - servo->get_output_min())) + servo->get_trim());
179  }
180 
181  return constrain_int16(ret, servo->get_output_min(), servo->get_output_max());
182 }
183 
184 // convert input in 0 to +1 range to pwm output
185 int16_t AP_Motors::calc_pwm_output_0to1(float input, const SRV_Channel *servo)
186 {
187  int16_t ret;
188 
189  input = constrain_float(input, 0.0f, 1.0f);
190 
191  if (servo->get_reversed()) {
192  input = 1.0f-input;
193  }
194 
195  ret = input * (servo->get_output_max() - servo->get_output_min()) + servo->get_output_min();
196 
197  return constrain_int16(ret, servo->get_output_min(), servo->get_output_max());
198 }
199 
200 /*
201  add a motor, setting up default output function as needed
202  */
203 void AP_Motors::add_motor_num(int8_t motor_num)
204 {
205  // ensure valid motor number is provided
206  if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
207  uint8_t chan;
209  SRV_Channels::set_aux_channel_default(function, motor_num);
210  if (!SRV_Channels::find_channel(function, chan)) {
211  gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
212  }
213  }
214 }
void reset(T value)
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel)
Definition: SRV_Channel.h:414
virtual void rc_write_angle(uint8_t chan, int16_t angle_cd)
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
static bool set_aux_channel_default(SRV_Channel::Aux_servo_function_t function, uint8_t channel)
Interface definition for the various Ground Control System.
virtual void set_freq(uint32_t chmask, uint16_t freq_hz)=0
struct AP_Motors::AP_Motors_flags _flags
uint16_t get_output_max(void) const
Definition: SRV_Channel.h:164
struct AP_Motors::AP_Motors_limit limit
GCS & gcs()
static uint16_t pwm
Definition: RCOutput.cpp:20
int16_t calc_pwm_output_0to1(float input, const SRV_Channel *servo)
void set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input)
void set_cutoff_frequency(float cutoff_freq)
static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan)
static AP_Motors * _instance
bool armed() const
virtual void save_params_on_disarm()
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
#define f(i)
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
int16_t calc_pwm_output_1to1(float input, const SRV_Channel *servo)
uint16_t get_output_min(void) const
Definition: SRV_Channel.h:161
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
float _throttle_radio_passthrough
virtual void set_output_mode(uint16_t mask, enum output_mode mode)
Definition: RCOutput.h:180
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
uint16_t get_trim(void) const
Definition: SRV_Channel.h:167
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void add_motor_num(int8_t motor_num)
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
static uint16_t get_output_channel_mask(SRV_Channel::Aux_servo_function_t function)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
float _roll_radio_passthrough
bool get_reversed(void) const
Definition: SRV_Channel.h:148
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
float _yaw_radio_passthrough
uint16_t _motor_fast_mask
AP_Int8 _pwm_type
#define AP_MOTORS_MAX_NUM_MOTORS
virtual uint32_t rc_map_mask(uint32_t mask) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14