APM:Libraries
SRV_Channel.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  SRV_Channel.cpp - object to separate input and output channel
17  ranges, trim and reversal
18  */
19 
20 #include <AP_HAL/AP_HAL.h>
21 #include <AP_Math/AP_Math.h>
22 #include <AP_Vehicle/AP_Vehicle.h>
23 #include <AP_Math/AP_Math.h>
24 #include "SRV_Channel.h"
25 
26 extern const AP_HAL::HAL& hal;
27 
29 
31  // @Param: MIN
32  // @DisplayName: Minimum PWM
33  // @Description: minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
34  // @Units: PWM
35  // @Range: 500 2200
36  // @Increment: 1
37  // @User: Standard
38  AP_GROUPINFO("MIN", 1, SRV_Channel, servo_min, 1100),
39 
40  // @Param: MAX
41  // @DisplayName: Maximum PWM
42  // @Description: maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
43  // @Units: PWM
44  // @Range: 800 2200
45  // @Increment: 1
46  // @User: Standard
47  AP_GROUPINFO("MAX", 2, SRV_Channel, servo_max, 1900),
48 
49  // @Param: TRIM
50  // @DisplayName: Trim PWM
51  // @Description: Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
52  // @Units: PWM
53  // @Range: 800 2200
54  // @Increment: 1
55  // @User: Standard
56  AP_GROUPINFO("TRIM", 3, SRV_Channel, servo_trim, 1500),
57 
58  // @Param: REVERSED
59  // @DisplayName: Servo reverse
60  // @Description: Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
61  // @Values: 0:Normal,1:Reversed
62  // @User: Standard
63  AP_GROUPINFO("REVERSED", 4, SRV_Channel, reversed, 0),
64 
65  // @Param: FUNCTION
66  // @DisplayName: Servo output function
67  // @Description: Function assigned to this servo. Seeing this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
68  // @Values: 0:Disabled,1:RCPassThru,2:Flap,3:Flap_auto,4:Aileron,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoilerLeft1,17:DifferentialSpoilerRight1,86:DifferentialSpoilerLeft2,87:DifferentialSpoilerRight2,19:Elevator,21:Rudder,24:FlaperonLeft,25:FlaperonRight,26:GroundSteering,27:Parachute,28:EPM,29:LandingGear,30:EngineRunEnable,31:HeliRSC,32:HeliTailRSC,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8,41:MotorTilt,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,67:Ignition,68:Choke,69:Starter,70:Throttle,71:TrackerYaw,72:TrackerPitch,73:ThrottleLeft,74:ThrottleRight,75:tiltMotorLeft,76:tiltMotorRight,77:ElevonLeft,78:ElevonRight,79:VTailLeft,80:VTailRight,81:BoostThrottle,82:Motor9,83:Motor10,84:Motor11,85:Motor12,88:Winch
69  // @User: Standard
70  AP_GROUPINFO("FUNCTION", 5, SRV_Channel, function, 0),
71 
73 };
74 
75 
77 {
79  // start with all pwm at zero
80  have_pwm_mask = ~uint16_t(0);
81 }
82 
83 // convert a 0..range_max to a pwm
84 uint16_t SRV_Channel::pwm_from_range(int16_t scaled_value) const
85 {
86  if (servo_max <= servo_min || high_out == 0) {
87  return servo_min;
88  }
89  scaled_value = constrain_int16(scaled_value, 0, high_out);
90  if (reversed) {
91  scaled_value = high_out - scaled_value;
92  }
93  return servo_min + ((int32_t)scaled_value * (int32_t)(servo_max - servo_min)) / (int32_t)high_out;
94 }
95 
96 // convert a -angle_max..angle_max to a pwm
97 uint16_t SRV_Channel::pwm_from_angle(int16_t scaled_value) const
98 {
99  if (reversed) {
100  scaled_value = -scaled_value;
101  }
102  scaled_value = constrain_int16(scaled_value, -high_out, high_out);
103  if (scaled_value > 0) {
104  return servo_trim + ((int32_t)scaled_value * (int32_t)(servo_max - servo_trim)) / (int32_t)high_out;
105  } else {
106  return servo_trim - (-(int32_t)scaled_value * (int32_t)(servo_trim - servo_min)) / (int32_t)high_out;
107  }
108 }
109 
110 void SRV_Channel::calc_pwm(int16_t output_scaled)
111 {
112  if (have_pwm_mask & (1U<<ch_num)) {
113  return;
114  }
115  uint16_t pwm;
116  if (type_angle) {
117  pwm = pwm_from_angle(output_scaled);
118  } else {
119  pwm = pwm_from_range(output_scaled);
120  }
121  set_output_pwm(pwm);
122 }
123 
125 {
126  output_pwm = pwm;
127  have_pwm_mask |= (1U<<ch_num);
128 }
129 
130 // set angular range of scaled output
131 void SRV_Channel::set_angle(int16_t angle)
132 {
133  type_angle = true;
134  high_out = angle;
135  type_setup = true;
136 }
137 
138 // set range of scaled output
139 void SRV_Channel::set_range(uint16_t high)
140 {
141  type_angle = false;
142  high_out = high;
143  type_setup = true;
144 }
145 
146 /*
147  get normalised output from -1 to 1, assuming 0 at mid point of servo_min/servo_max
148  */
150 {
151  uint16_t mid = (servo_max + servo_min) / 2;
152  float ret;
153  if (mid <= servo_min) {
154  return 0;
155  }
156  if (output_pwm < mid) {
157  ret = (float)(output_pwm - mid) / (float)(mid - servo_min);
158  } else if (output_pwm > mid) {
159  ret = (float)(output_pwm - mid) / (float)(servo_max - mid);
160  } else {
161  ret = 0;
162  }
163  if (get_reversed()) {
164  ret = -ret;
165  }
166  return ret;
167 }
168 
170 {
171  switch (limit) {
173  return servo_trim;
175  return servo_min;
177  return servo_max;
179  default:
180  return 0;
181  }
182 }
183 
184 // return true if function is for a multicopter motor
186 {
187  return ((function >= SRV_Channel::k_motor1 && function <= SRV_Channel::k_motor8) ||
188  (function >= SRV_Channel::k_motor9 && function <= SRV_Channel::k_motor12));
189 }
bool type_angle
Definition: SRV_Channel.h:208
SRV_Channel(void)
Definition: SRV_Channel.cpp:76
uint16_t get_limit_pwm(LimitValue limit) const
static bool is_motor(SRV_Channel::Aux_servo_function_t function)
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
uint16_t pwm_from_range(int16_t scaled_value) const
Definition: SRV_Channel.cpp:84
void set_angle(int16_t angle)
bool type_setup
Definition: SRV_Channel.h:211
void set_range(uint16_t high)
float get_output_norm(void)
uint8_t ch_num
Definition: SRV_Channel.h:214
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Int16 servo_trim
Definition: SRV_Channel.h:199
static uint16_t pwm
Definition: RCOutput.cpp:20
uint16_t pwm_from_angle(int16_t scaled_value) const
Definition: SRV_Channel.cpp:97
AP_Int16 servo_max
Definition: SRV_Channel.h:198
AP_Int16 servo_min
Definition: SRV_Channel.h:197
uint16_t output_pwm
Definition: SRV_Channel.h:205
these allow remapping of copter motors
Definition: SRV_Channel.h:77
AP_Int8 reversed
Definition: SRV_Channel.h:201
bool get_reversed(void) const
Definition: SRV_Channel.h:148
static servo_mask_t have_pwm_mask
Definition: SRV_Channel.h:245
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint16_t servo_mask_t
Definition: SRV_Channel.h:241
static const struct AP_Param::GroupInfo var_info[]
Definition: SRV_Channel.h:40
void set_output_pwm(uint16_t pwm)
void calc_pwm(int16_t output_scaled)
uint16_t high_out
Definition: SRV_Channel.h:217
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214