APM:Libraries
AP_Proximity_LightWareSF40C.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>
19 #include <ctype.h>
20 #include <stdio.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 /*
25  The constructor also initialises the proximity sensor. Note that this
26  constructor is not called until detect() returns true, so we
27  already know that we should setup the proximity sensor
28 */
32  AP_Proximity_Backend(_frontend, _state)
33 {
35  if (uart != nullptr) {
37  }
38 }
39 
40 // detect if a Lightware proximity sensor is connected by looking for a configured serial port
42 {
43  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0) != nullptr;
44 }
45 
46 // update the state of the sensor
48 {
49  if (uart == nullptr) {
50  return;
51  }
52 
53  // initialise sensor if necessary
54  bool initialised = initialise();
55 
56  // process incoming messages
58 
59  // request new data from sensor
60  if (initialised) {
62  }
63 
64  // check for timeout and set health status
67  } else {
69  }
70 }
71 
72 // get maximum and minimum distances (in meters) of primary sensor
74 {
75  return 100.0f;
76 }
78 {
79  return 0.20f;
80 }
81 
82 // initialise sensor (returns true if sensor is succesfully initialised)
84 {
85  // set motor direction once per second
86  if (_motor_direction > 1) {
87  if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
89  }
90  }
91  // set forward direction once per second
93  if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
95  }
96  }
97  // request motors turn on once per second
98  if (_motor_speed == 0) {
99  if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
100  set_motor_speed(true);
101  }
102  return false;
103  }
104  // initialise sectors
105  if (!_sector_initialised) {
106  init_sectors();
107  return false;
108  }
109  return true;
110 }
111 
112 // initialise sector angles using user defined ignore areas
114 {
115  // use defaults if no ignore areas defined
116  uint8_t ignore_area_count = get_ignore_area_count();
117  if (ignore_area_count == 0) {
118  _sector_initialised = true;
119  return;
120  }
121 
122  uint8_t sector = 0;
123 
124  for (uint8_t i=0; i<ignore_area_count; i++) {
125 
126  // get ignore area info
127  uint16_t ign_area_angle;
128  uint8_t ign_area_width;
129  if (get_ignore_area(i, ign_area_angle, ign_area_width)) {
130 
131  // calculate how many degrees of space we have between this end of this ignore area and the start of the end
132  int16_t start_angle, end_angle;
133  get_next_ignore_start_or_end(1, ign_area_angle, start_angle);
134  get_next_ignore_start_or_end(0, start_angle, end_angle);
135  int16_t degrees_to_fill = wrap_360(end_angle - start_angle);
136 
137  // divide up the area into sectors
138  while ((degrees_to_fill > 0) && (sector < PROXIMITY_SECTORS_MAX)) {
139  uint16_t sector_size;
140  if (degrees_to_fill >= 90) {
141  // set sector to maximum of 45 degrees
142  sector_size = 45;
143  } else if (degrees_to_fill > 45) {
144  // use half the remaining area to optimise size of this sector and the next
145  sector_size = degrees_to_fill / 2.0f;
146  } else {
147  // 45 degrees or less are left so put it all into the next sector
148  sector_size = degrees_to_fill;
149  }
150  // record the sector middle and width
151  _sector_middle_deg[sector] = wrap_360(start_angle + sector_size / 2.0f);
152  _sector_width_deg[sector] = sector_size;
153 
154  // move onto next sector
155  start_angle += sector_size;
156  sector++;
157  degrees_to_fill -= sector_size;
158  }
159  }
160  }
161 
162  // set num sectors
163  _num_sectors = sector;
164 
165  // re-initialise boundary because sector locations have changed
166  init_boundary();
167 
168  // record success
169  _sector_initialised = true;
170 }
171 
172 // set speed of rotating motor
174 {
175  // exit immediately if no uart
176  if (uart == nullptr) {
177  return;
178  }
179 
180  // set motor update speed
181  if (on_off) {
182  uart->write("#MBS,3\r\n"); // send request to spin motor at 4.5hz
183  } else {
184  uart->write("#MBS,0\r\n"); // send request to stop motor
185  }
186 
187  // request update motor speed
188  uart->write("?MBS\r\n");
191 }
192 
193 // set spin direction of motor
195 {
196  // exit immediately if no uart
197  if (uart == nullptr) {
198  return;
199  }
200 
201  // set motor update speed
203  uart->write("#MBD,0\r\n"); // spin clockwise
204  } else {
205  uart->write("#MBD,1\r\n"); // spin counter clockwise
206  }
207 
208  // request update on motor direction
209  uart->write("?MBD\r\n");
212 }
213 
214 // set forward direction (to allow rotating lidar)
216 {
217  // exit immediately if no uart
218  if (uart == nullptr) {
219  return;
220  }
221 
222  // set forward direction
223  char request_str[15];
224  int16_t yaw_corr = frontend.get_yaw_correction(state.instance);
225  yaw_corr = constrain_int16(yaw_corr, -999, 999);
226  snprintf(request_str, sizeof(request_str), "#MBF,%d\r\n", yaw_corr);
227  uart->write(request_str);
228 
229  // request update on motor direction
230  uart->write("?MBF\r\n");
233 }
234 
235 // request new data if required
237 {
238  if (uart == nullptr) {
239  return;
240  }
241 
242  // after timeout assume no reply will ever come
243  uint32_t now = AP_HAL::millis();
246  _last_request_ms = 0;
247  }
248 
249  // if we are not waiting for a reply, ask for something
251  _request_count++;
252  if (_request_count >= 5) {
254  _request_count = 0;
255  } else {
256  // request new distance measurement
258  }
259  _last_request_ms = now;
260  }
261 }
262 
263 // send request for sensor health
265 {
266  if (uart == nullptr) {
267  return;
268  }
269 
270  uart->write("?GS\r\n");
273 }
274 
275 // send request for distance from the next sector
277 {
278  if (uart == nullptr) {
279  return false;
280  }
281 
282  // increment sector
283  _last_sector++;
284  if (_last_sector >= _num_sectors) {
285  _last_sector = 0;
286  }
287 
288  // prepare request
289  char request_str[16];
290  snprintf(request_str, sizeof(request_str), "?TS,%u,%u\r\n",
292  MIN(_sector_middle_deg[_last_sector], 999));
293  uart->write(request_str);
294 
295 
296  // record request for distance
299 
300  return true;
301 }
302 
303 // check for replies from sensor, returns true if at least one message was processed
305 {
306  if (uart == nullptr) {
307  return false;
308  }
309 
310  // read any available lines from the lidar
311  // if CR (i.e. \r), LF (\n) it means we have received a full packet so send for processing
312  // lines starting with # are ignored because this is the echo of a set-motor request which has no reply
313  // lines starting with ? are the echo back of our distance request followed by the sensed distance
314  // distance data appears after a <space>
315  // distance data is comma separated so we put into separate elements (i.e. <space>angle,distance)
316  uint16_t count = 0;
317  int16_t nbytes = uart->available();
318  while (nbytes-- > 0) {
319  char c = uart->read();
320  // check for end of packet
321  if (c == '\r' || c == '\n') {
322  if ((element_len[0] > 0)) {
323  if (process_reply()) {
324  count++;
325  }
326  }
327  // clear buffers after processing
328  clear_buffers();
329  ignore_reply = false;
330  wait_for_space = false;
331 
332  // if message starts with # ignore it
333  } else if (c == '#' || ignore_reply) {
334  ignore_reply = true;
335 
336  // if waiting for <space>
337  } else if (c == '?') {
338  wait_for_space = true;
339 
340  } else if (wait_for_space) {
341  if (c == ' ') {
342  wait_for_space = false;
343  }
344 
345  // if comma, move onto filling in 2nd element
346  } else if (c == ',') {
347  if ((element_num == 0) && (element_len[0] > 0)) {
348  element_num++;
349  } else {
350  // don't support 3rd element so clear buffers
351  clear_buffers();
352  ignore_reply = true;
353  }
354 
355  // if part of a number, add to element buffer
356  } else if (isdigit(c) || c == '.' || c == '-') {
358  element_len[element_num]++;
359  if (element_len[element_num] >= sizeof(element_buf[element_num])-1) {
360  // too long, discard the line
361  clear_buffers();
362  ignore_reply = true;
363  }
364  }
365  }
366 
367  return (count > 0);
368 }
369 
370 // process reply
372 {
373  if (uart == nullptr) {
374  return false;
375  }
376 
377  bool success = false;
378 
379  switch (_last_request_type) {
380  case RequestType_None:
381  break;
382 
383  case RequestType_Health:
384  // expect result in the form "0xhhhh"
385  if (element_len[0] > 0) {
386  int result;
387  if (sscanf(element_buf[0], "%x", &result) > 0) {
388  _sensor_status.value = result;
389  success = true;
390  }
391  }
392  break;
393 
395  _motor_speed = atoi(element_buf[0]);
396  success = true;
397  break;
398 
400  _motor_direction = atoi(element_buf[0]);
401  success = true;
402  break;
403 
405  _forward_direction = atoi(element_buf[0]);
406  success = true;
407  break;
408 
410  {
411  float angle_deg = (float)atof(element_buf[0]);
412  float distance_m = (float)atof(element_buf[1]);
413  uint8_t sector;
414  if (convert_angle_to_sector(angle_deg, sector)) {
415  _angle[sector] = angle_deg;
416  _distance[sector] = distance_m;
417  _distance_valid[sector] = is_positive(distance_m);
419  success = true;
420  // update boundary used for avoidance
422  }
423  break;
424  }
425 
426  default:
427  break;
428  }
429 
430  // mark request as cleared
431  if (success) {
433  }
434 
435  return success;
436 }
437 
438 // clear buffers ahead of processing next message
440 {
441  element_len[0] = 0;
442  element_len[1] = 0;
443  element_num = 0;
444  memset(element_buf, 0, sizeof(element_buf));
445 }
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
bool _distance_valid[PROXIMITY_SECTORS_MAX]
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
union AP_Proximity_LightWareSF40C::@166 _sensor_status
float _angle[PROXIMITY_SECTORS_MAX]
virtual void begin(uint32_t baud)=0
AP_Proximity_LightWareSF40C(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager)
#define PROXIMITY_SF40C_TIMEOUT_MS
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 _sector_middle_deg[PROXIMITY_SECTORS_MAX]
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
int16_t get_yaw_correction(uint8_t instance) const
void set_status(AP_Proximity::Proximity_Status status)
const char * result
Definition: Printf.cpp:16
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
#define MIN(a, b)
Definition: usb_conf.h:215
bool convert_angle_to_sector(float angle_degrees, uint8_t &sector) const
uint8_t get_ignore_area_count() const
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
float _distance[PROXIMITY_SECTORS_MAX]
static bool detect(AP_SerialManager &serial_manager)
#define f(i)
int sscanf(const char *buf, const char *fmt,...)
Definition: stdio.c:136
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
virtual int16_t read()=0
virtual uint32_t available()=0
AP_Proximity::Proximity_State & state
bool get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
uint8_t _sector_width_deg[PROXIMITY_SECTORS_MAX]
bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const
void update_boundary_for_sector(uint8_t sector)
#define PROXIMITY_SECTORS_MAX
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
uint8_t get_orientation(uint8_t instance) const