APM:Libraries
AP_RangeFinder_Wasp.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_HAL/AP_HAL.h>
17 #include "AP_RangeFinder_Wasp.h"
19 #include <ctype.h>
20 
21 extern const AP_HAL::HAL& hal;
22 
24  // @Param: WSP_MAVG
25  // @DisplayName: Moving Average Range
26  // @Description: Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
27  // @Range: 0 255
28  // @User: Advanced
29  AP_GROUPINFO("WSP_MAVG", 1, AP_RangeFinder_Wasp, mavg, 4),
30 
31  // @Param: WSP_MEDF
32  // @DisplayName: Moving Median Filter
33  // @Description: Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
34  // @Range: 0 255
35  // @User: Advanced
36  AP_GROUPINFO("WSP_MEDF", 2, AP_RangeFinder_Wasp, medf, 4),
37 
38  // @Param: WSP_FRQ
39  // @DisplayName: Frequency
40  // @Description: Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
41  // @Range: 0 10000
42  // @User: Advanced
43  AP_GROUPINFO("WSP_FRQ", 3, AP_RangeFinder_Wasp, frq, 100),
44 
45  // @Param: WSP_AVG
46  // @DisplayName: Multi-pulse averages
47  // @Description: Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
48  // @Range: 0 255
49  // @User: Advanced
50  AP_GROUPINFO("WSP_AVG", 4, AP_RangeFinder_Wasp, avg, 4),
51 
52  // @Param: WSP_THR
53  // @DisplayName: Sensitivity threshold
54  // @Description: Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
55  // @Range: -1 255
56  // @User: Advanced
57  AP_GROUPINFO("WSP_THR", 5, AP_RangeFinder_Wasp, thr, -1),
58 
60 };
61 
62 
65  uint8_t serial_instance) :
66  AP_RangeFinder_Backend(_state) {
68 
69  uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
70  if (uart != nullptr) {
71  uart->begin(115200);
72 
73  // register Wasp specific parameters
75 
77  }
78 }
79 
80 // detection is considered as locating a serial port
82  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
83 }
84 
85 // read - return last value measured by sensor
86 bool AP_RangeFinder_Wasp::get_reading(uint16_t &reading_cm) {
87  if (uart == nullptr) {
88  return false;
89  }
90 
91  // read any available lines from the lidar
92  float sum = 0;
93  uint16_t count = 0;
94  int16_t nbytes = uart->available();
95  while (nbytes-- > 0) {
96  char c = uart->read();
97  if (c == '\n') {
98  linebuf[linebuf_len] = 0;
99  linebuf_len = 0;
101  if (isalpha(linebuf[0])) {
102  parse_response();
103  } else {
104  float read_value = (float)atof(linebuf);
105  if (read_value > 0) {
106  sum += read_value;
107  count++;
108  }
109  }
110  } else if (isalnum(c) || c == '.' || c == '-') {
111  linebuf[linebuf_len++] = c;
112  }
113 
114  // discard excessively long buffers
115  if (linebuf_len == sizeof(linebuf)) {
116  linebuf_len = 0;
117  }
118  }
119 
120  if (configuration_state == WASP_CFG_RATE && uart->tx_pending() == 0) {
122  }
123 
124  if (count == 0) {
125  return false;
126  }
127 
128  reading_cm = 100 * sum / count;
130 
131  return true;
132 }
133 
134 #define COMMAND_BUFFER_LEN 15
135 
137  if (!get_reading(state.distance_cm)) {
139  }
140 
141  if (AP_HAL::millis() - last_reading_ms > 500) {
142  // attempt to reconfigure on the assumption this was a bad baud setting
144  }
145 
146  char command[COMMAND_BUFFER_LEN] = {};
147 
148  switch (configuration_state) {
149  case WASP_CFG_RATE:
150  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">BAUD %s\n", baud > 0 ? "HIGH" : "LOW");
151  break;
152  case WASP_CFG_ENCODING:
153  uart->end();
154  uart->begin(baud > 0 ? 912600 : 115200);
155  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">LBE LITTLE\n");
156  break;
157  case WASP_CFG_PROTOCOL:
158  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">FMT ASCII\n");
159  break;
160  case WASP_CFG_FRQ:
161  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">FRQ %d\n", constrain_int16(frq, 20, baud > 0 ? 10000 : 1440));
162  break;
163  case WASP_CFG_GO:
164  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">GO\n");
165  break;
166  case WASP_CFG_AUT:
167  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">AUT %d\n", thr >= 0 ? 0 : 1);
168  break;
169  case WASP_CFG_THR:
170  if (thr >= 0) {
171  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">THR %d\n", constrain_int16(thr, 0,255));
172  } else {
174  }
175  break;
176  case WASP_CFG_MAVG:
177  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">MAVG %d\n", constrain_int16(mavg, 0, 255));
178  break;
179  case WASP_CFG_MEDF:
180  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">MEDF %d\n", constrain_int16(medf, 0, 255));
181  break;
182  case WASP_CFG_AVG:
183  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">AVG %d\n", constrain_int16(avg, 0, 255));
184  break;
185  case WASP_CFG_AUV:
186  hal.util->snprintf(command, COMMAND_BUFFER_LEN, ">AUV 1\n");
187  break;
188  case WASP_CFG_DONE:
189  return;
190  }
191 
192  if (command[0] != 0) {
193  uart->write((uint8_t *)command, strlen(command));
194  }
195 }
196 
198  switch (configuration_state) {
199  case WASP_CFG_RATE:
201  break;
202  case WASP_CFG_ENCODING:
203  if (strncmp(linebuf, "LBE", 3) == 0) {
205  }
206  break;
207  case WASP_CFG_PROTOCOL:
208  if (strncmp(linebuf, "FMT", 3) == 0) {
210  }
211  break;
212  case WASP_CFG_FRQ:
213  if (strncmp(linebuf, "FRQ", 3) == 0) {
215  }
216  break;
217  case WASP_CFG_GO:
218  if (strncmp(linebuf, "GO", 2) == 0) {
220  }
221  break;
222  case WASP_CFG_AUT:
223  if (strncmp(linebuf, "AUT", 3) == 0) {
225  }
226  break;
227  case WASP_CFG_THR:
228  if (strncmp(linebuf, "THR", 3) == 0) {
230  }
231  break;
232  case WASP_CFG_MAVG:
233  if (strncmp(linebuf, "MAVG", 4) == 0) {
235  }
236  break;
237  case WASP_CFG_MEDF:
238  if (strncmp(linebuf, "MEDF", 4) == 0) {
240  }
241  break;
242  case WASP_CFG_AVG:
243  if (strncmp(linebuf, "AVG", 3) == 0) {
245  }
246  break;
247  case WASP_CFG_AUV:
248  if (strncmp(linebuf, "AUV", 3) == 0) {
250  }
251  break;
252  case WASP_CFG_DONE:
253  return;
254  }
255 }
256 
wasp_configuration_stage configuration_state
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
virtual bool tx_pending()=0
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
virtual void begin(uint32_t baud)=0
void update(void) override
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_HAL::Util * util
Definition: HAL.h:115
bool get_reading(uint16_t &reading_cm)
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
AP_HAL::UARTDriver * uart
static const struct AP_Param::GroupInfo var_info[]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define COMMAND_BUFFER_LEN
AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual void end()=0
virtual int16_t read()=0
virtual uint32_t available()=0
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
const struct AP_Param::GroupInfo * var_info
Definition: RangeFinder.h:106
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214