APM:Libraries
AP_WheelEncoder.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 #include "AP_WheelEncoder.h"
18 
19 extern const AP_HAL::HAL& hal;
20 
21 // table of user settable parameters
23  // @Param: _TYPE
24  // @DisplayName: WheelEncoder type
25  // @Description: What type of WheelEncoder is connected
26  // @Values: 0:None,1:Quadrature
27  // @User: Standard
28  AP_GROUPINFO_FLAGS("_TYPE", 0, AP_WheelEncoder, _type[0], 0, AP_PARAM_FLAG_ENABLE),
29 
30  // @Param: _CPR
31  // @DisplayName: WheelEncoder counts per revolution
32  // @Description: WheelEncoder counts per full revolution of the wheel
33  // @Increment: 1
34  // @User: Standard
35  AP_GROUPINFO("_CPR", 1, AP_WheelEncoder, _counts_per_revolution[0], WHEELENCODER_CPR_DEFAULT),
36 
37  // @Param: _RADIUS
38  // @DisplayName: Wheel radius in meters
39  // @Description: Wheel radius in meters
40  // @Increment: 0.001
41  // @User: Standard
42  AP_GROUPINFO("_RADIUS", 2, AP_WheelEncoder, _wheel_radius[0], WHEELENCODER_RADIUS_DEFAULT),
43 
44  // @Param: _POS_X
45  // @DisplayName: Wheel's X position offset
46  // @Description: X position of the center of the wheel in body frame. Positive X is forward of the origin.
47  // @Units: m
48  // @Increment: 0.01
49  // @User: Advanced
50 
51  // @Param: _POS_Y
52  // @DisplayName: Wheel's Y position offset
53  // @Description: Y position of the center of the wheel in body frame. Positive Y is to the right of the origin.
54  // @Units: m
55  // @Increment: 0.01
56  // @User: Advanced
57 
58  // @Param: _POS_Z
59  // @DisplayName: Wheel's Z position offset
60  // @Description: Z position of the center of the wheel in body frame. Positive Z is down from the origin.
61  // @Units: m
62  // @Increment: 0.01
63  // @User: Advanced
64  AP_GROUPINFO("_POS", 3, AP_WheelEncoder, _pos_offset[0], 0.0f),
65 
66  // @Param: _PINA
67  // @DisplayName: Input Pin A
68  // @Description: Input Pin A
69  // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
70  // @User: Standard
71  AP_GROUPINFO("_PINA", 4, AP_WheelEncoder, _pina[0], 55),
72 
73  // @Param: _PINB
74  // @DisplayName: Input Pin B
75  // @Description: Input Pin B
76  // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
77  // @User: Standard
78  AP_GROUPINFO("_PINB", 5, AP_WheelEncoder, _pinb[0], 54),
79 
80 #if WHEELENCODER_MAX_INSTANCES > 1
81  // @Param: 2_TYPE
82  // @DisplayName: Second WheelEncoder type
83  // @Description: What type of WheelEncoder sensor is connected
84  // @Values: 0:None,1:Quadrature
85  // @User: Standard
86  AP_GROUPINFO("2_TYPE", 6, AP_WheelEncoder, _type[1], 0),
87 
88  // @Param: 2_CPR
89  // @DisplayName: WheelEncoder 2 counts per revolution
90  // @Description: WheelEncoder 2 counts per full revolution of the wheel
91  // @Increment: 1
92  // @User: Standard
93  AP_GROUPINFO("2_CPR", 7, AP_WheelEncoder, _counts_per_revolution[1], WHEELENCODER_CPR_DEFAULT),
94 
95  // @Param: 2_RADIUS
96  // @DisplayName: Wheel2's radius in meters
97  // @Description: Wheel2's radius in meters
98  // @Increment: 0.001
99  // @User: Standard
100  AP_GROUPINFO("2_RADIUS", 8, AP_WheelEncoder, _wheel_radius[1], WHEELENCODER_RADIUS_DEFAULT),
101 
102  // @Param: 2_POS_X
103  // @DisplayName: Wheel2's X position offset
104  // @Description: X position of the center of the second wheel in body frame. Positive X is forward of the origin.
105  // @Units: m
106  // @Increment: 0.01
107  // @User: Advanced
108 
109  // @Param: 2_POS_Y
110  // @DisplayName: Wheel2's Y position offset
111  // @Description: Y position of the center of the second wheel in body frame. Positive Y is to the right of the origin.
112  // @Units: m
113  // @Increment: 0.01
114  // @User: Advanced
115 
116  // @Param: 2_POS_Z
117  // @DisplayName: Wheel2's Z position offset
118  // @Description: Z position of the center of the second wheel in body frame. Positive Z is down from the origin.
119  // @Units: m
120  // @Increment: 0.01
121  // @User: Advanced
122  AP_GROUPINFO("2_POS", 9, AP_WheelEncoder, _pos_offset[1], 0.0f),
123 
124  // @Param: 2_PINA
125  // @DisplayName: Second Encoder Input Pin A
126  // @Description: Second Encoder Input Pin A
127  // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
128  // @User: Standard
129  AP_GROUPINFO("2_PINA", 10, AP_WheelEncoder, _pina[1], 53),
130 
131  // @Param: 2_PINB
132  // @DisplayName: Second Encoder Input Pin B
133  // @Description: Second Encoder Input Pin B
134  // @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
135  // @User: Standard
136  AP_GROUPINFO("2_PINB", 11, AP_WheelEncoder, _pinb[1], 52),
137 #endif
138 
140 };
141 
143  num_instances(0)
144 {
146 
147  // init state and drivers
148  memset(state, 0, sizeof(state));
149  memset(drivers, 0, sizeof(drivers));
150 }
151 
152 // initialise the AP_WheelEncoder class.
154 {
155  if (num_instances != 0) {
156  // init called a 2nd time?
157  return;
158  }
159  for (uint8_t i=0; i<WHEELENCODER_MAX_INSTANCES; i++) {
160 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
161  uint8_t type = _type[num_instances];
162  uint8_t instance = num_instances;
163 
164  if (type == WheelEncoder_TYPE_QUADRATURE) {
165  state[instance].instance = instance;
166  drivers[instance] = new AP_WheelEncoder_Quadrature(*this, instance, state[instance]);
167  }
168 #endif
169 
170  if (drivers[i] != nullptr) {
171  // we loaded a driver for this instance, so it must be
172  // present (although it may not be healthy)
173  num_instances = i+1;
174  }
175  }
176 }
177 
178 // update WheelEncoder state for all instances. This should be called by main loop
180 {
181  for (uint8_t i=0; i<num_instances; i++) {
182  if (drivers[i] != nullptr && _type[i] != WheelEncoder_TYPE_NONE) {
183  drivers[i]->update();
184  }
185  }
186 }
187 
188 // check if an instance is healthy
189 bool AP_WheelEncoder::healthy(uint8_t instance) const
190 {
191  if (instance >= num_instances) {
192  return false;
193  }
194  return true;
195 }
196 
197 // check if an instance is activated
198 bool AP_WheelEncoder::enabled(uint8_t instance) const
199 {
200  if (instance >= num_instances) {
201  return false;
202  }
203  // if no sensor type is selected, the sensor is not activated.
204  if (_type[instance] == WheelEncoder_TYPE_NONE) {
205  return false;
206  }
207  return true;
208 }
209 
210 // get the counts per revolution of the encoder
211 uint16_t AP_WheelEncoder::get_counts_per_revolution(uint8_t instance) const
212 {
213  // for invalid instances return zero vector
214  if (instance >= WHEELENCODER_MAX_INSTANCES) {
215  return 0;
216  }
217  return (uint16_t)_counts_per_revolution[instance];
218 }
219 
220 // get the wheel radius in meters
221 float AP_WheelEncoder::get_wheel_radius(uint8_t instance) const
222 {
223  // for invalid instances return zero vector
224  if (instance >= WHEELENCODER_MAX_INSTANCES) {
225  return 0.0f;
226  }
227  return _wheel_radius[instance];
228 }
229 
230 // get the total distance travelled in meters
232 {
233  // for invalid instances return zero vector
234  if (instance >= WHEELENCODER_MAX_INSTANCES) {
235  return Vector3f();
236  }
237  return _pos_offset[instance];
238 }
239 
240 // get total delta angle (in radians) measured by the wheel encoder
241 float AP_WheelEncoder::get_delta_angle(uint8_t instance) const
242 {
243  // for invalid instances return zero
244  if (instance >= WHEELENCODER_MAX_INSTANCES) {
245  return 0.0f;
246  }
247  // protect against divide by zero
248  if (_counts_per_revolution[instance] == 0) {
249  return 0.0f;
250  }
251  return M_2PI * state[instance].distance_count / _counts_per_revolution[instance];
252 }
253 
254 // get the total distance traveled in meters
255 float AP_WheelEncoder::get_distance(uint8_t instance) const
256 {
257  // for invalid instances return zero
258  return get_delta_angle(instance) * _wheel_radius[instance];
259 }
260 
261 // get the total number of sensor reading from the encoder
262 uint32_t AP_WheelEncoder::get_total_count(uint8_t instance) const
263 {
264  // for invalid instances return zero
265  if (instance >= WHEELENCODER_MAX_INSTANCES) {
266  return 0;
267  }
268  return state[instance].total_count;
269 }
270 
271 // get the total distance traveled in meters
272 uint32_t AP_WheelEncoder::get_error_count(uint8_t instance) const
273 {
274  // for invalid instances return zero
275  if (instance >= WHEELENCODER_MAX_INSTANCES) {
276  return 0;
277  }
278  return state[instance].error_count;
279 }
280 
281 // get the signal quality for a sensor
282 float AP_WheelEncoder::get_signal_quality(uint8_t instance) const
283 {
284  // protect against divide by zero
285  if (state[instance].total_count == 0) {
286  return 0.0f;
287  }
288  return constrain_float((1.0f - ((float)state[instance].error_count / (float)state[instance].total_count)) * 100.0f, 0.0f, 100.0f);
289 }
290 
291 // get the system time (in milliseconds) of the last update
292 uint32_t AP_WheelEncoder::get_last_reading_ms(uint8_t instance) const
293 {
294  // for invalid instances return zero
295  if (instance >= WHEELENCODER_MAX_INSTANCES) {
296  return 0;
297  }
298  return state[instance].last_reading_ms;
299 }
Vector3< float > Vector3f
Definition: vector3.h:246
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
AP_Int8 _type[WHEELENCODER_MAX_INSTANCES]
WheelEncoder_State state[WHEELENCODER_MAX_INSTANCES]
float get_wheel_radius(uint8_t instance) const
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
uint32_t get_total_count(uint8_t instance) const
friend class AP_WheelEncoder_Quadrature
AP_Int16 _counts_per_revolution[WHEELENCODER_MAX_INSTANCES]
uint32_t get_last_reading_ms(uint8_t instance) const
#define WHEELENCODER_MAX_INSTANCES
static const struct AP_Param::GroupInfo var_info[]
#define WHEELENCODER_CPR_DEFAULT
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
uint32_t get_error_count(uint8_t instance) const
#define f(i)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
float get_distance(uint8_t instance) const
Vector3f get_position(uint8_t instance) const
bool healthy(uint8_t instance) const
virtual void update()=0
bool enabled(uint8_t instance) const
AP_Float _wheel_radius[WHEELENCODER_MAX_INSTANCES]
#define M_2PI
Definition: definitions.h:19
float get_signal_quality(uint8_t instance) const
#define WHEELENCODER_RADIUS_DEFAULT
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
uint16_t get_counts_per_revolution(uint8_t instance) const
AP_Vector3f _pos_offset[WHEELENCODER_MAX_INSTANCES]
AP_WheelEncoder_Backend * drivers[WHEELENCODER_MAX_INSTANCES]
float get_delta_angle(uint8_t instance) const
#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