AP_Proximity_LightWareSF40C.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include <AP_HAL/AP_HAL.h>
  14. #include "AP_Proximity_LightWareSF40C.h"
  15. #include <AP_SerialManager/AP_SerialManager.h>
  16. #include <ctype.h>
  17. #include <stdio.h>
  18. extern const AP_HAL::HAL& hal;
  19. /*
  20. The constructor also initialises the proximity sensor. Note that this
  21. constructor is not called until detect() returns true, so we
  22. already know that we should setup the proximity sensor
  23. */
  24. AP_Proximity_LightWareSF40C::AP_Proximity_LightWareSF40C(AP_Proximity &_frontend,
  25. AP_Proximity::Proximity_State &_state,
  26. AP_SerialManager &serial_manager) :
  27. AP_Proximity_Backend(_frontend, _state)
  28. {
  29. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0);
  30. if (uart != nullptr) {
  31. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar360, 0));
  32. }
  33. }
  34. // detect if a Lightware proximity sensor is connected by looking for a configured serial port
  35. bool AP_Proximity_LightWareSF40C::detect(AP_SerialManager &serial_manager)
  36. {
  37. return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0) != nullptr;
  38. }
  39. // update the state of the sensor
  40. void AP_Proximity_LightWareSF40C::update(void)
  41. {
  42. if (uart == nullptr) {
  43. return;
  44. }
  45. // initialise sensor if necessary
  46. bool initialised = initialise();
  47. // process incoming messages
  48. check_for_reply();
  49. // request new data from sensor
  50. if (initialised) {
  51. request_new_data();
  52. }
  53. // check for timeout and set health status
  54. if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_SF40C_TIMEOUT_MS)) {
  55. set_status(AP_Proximity::Proximity_NoData);
  56. } else {
  57. set_status(AP_Proximity::Proximity_Good);
  58. }
  59. }
  60. // get maximum and minimum distances (in meters) of primary sensor
  61. float AP_Proximity_LightWareSF40C::distance_max() const
  62. {
  63. return 100.0f;
  64. }
  65. float AP_Proximity_LightWareSF40C::distance_min() const
  66. {
  67. return 0.20f;
  68. }
  69. // initialise sensor (returns true if sensor is succesfully initialised)
  70. bool AP_Proximity_LightWareSF40C::initialise()
  71. {
  72. // set motor direction once per second
  73. if (_motor_direction > 1) {
  74. if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
  75. set_motor_direction();
  76. }
  77. }
  78. // set forward direction once per second
  79. if (_forward_direction != frontend.get_yaw_correction(state.instance)) {
  80. if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
  81. set_forward_direction();
  82. }
  83. }
  84. // request motors turn on once per second
  85. if (_motor_speed == 0) {
  86. if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
  87. set_motor_speed(true);
  88. }
  89. return false;
  90. }
  91. // initialise sectors
  92. if (!_sector_initialised) {
  93. init_sectors();
  94. return false;
  95. }
  96. return true;
  97. }
  98. // initialise sector angles using user defined ignore areas
  99. void AP_Proximity_LightWareSF40C::init_sectors()
  100. {
  101. // use defaults if no ignore areas defined
  102. uint8_t ignore_area_count = get_ignore_area_count();
  103. if (ignore_area_count == 0) {
  104. _sector_initialised = true;
  105. return;
  106. }
  107. uint8_t sector = 0;
  108. for (uint8_t i=0; i<ignore_area_count; i++) {
  109. // get ignore area info
  110. uint16_t ign_area_angle;
  111. uint8_t ign_area_width;
  112. if (get_ignore_area(i, ign_area_angle, ign_area_width)) {
  113. // calculate how many degrees of space we have between this end of this ignore area and the start of the end
  114. int16_t start_angle, end_angle;
  115. get_next_ignore_start_or_end(1, ign_area_angle, start_angle);
  116. get_next_ignore_start_or_end(0, start_angle, end_angle);
  117. int16_t degrees_to_fill = wrap_360(end_angle - start_angle);
  118. // divide up the area into sectors
  119. while ((degrees_to_fill > 0) && (sector < PROXIMITY_SECTORS_MAX)) {
  120. uint16_t sector_size;
  121. if (degrees_to_fill >= 90) {
  122. // set sector to maximum of 45 degrees
  123. sector_size = 45;
  124. } else if (degrees_to_fill > 45) {
  125. // use half the remaining area to optimise size of this sector and the next
  126. sector_size = degrees_to_fill / 2.0f;
  127. } else {
  128. // 45 degrees or less are left so put it all into the next sector
  129. sector_size = degrees_to_fill;
  130. }
  131. // record the sector middle and width
  132. _sector_middle_deg[sector] = wrap_360(start_angle + sector_size / 2.0f);
  133. _sector_width_deg[sector] = sector_size;
  134. // move onto next sector
  135. start_angle += sector_size;
  136. sector++;
  137. degrees_to_fill -= sector_size;
  138. }
  139. }
  140. }
  141. // set num sectors
  142. _num_sectors = sector;
  143. // re-initialise boundary because sector locations have changed
  144. init_boundary();
  145. // record success
  146. _sector_initialised = true;
  147. }
  148. // set speed of rotating motor
  149. void AP_Proximity_LightWareSF40C::set_motor_speed(bool on_off)
  150. {
  151. // exit immediately if no uart
  152. if (uart == nullptr) {
  153. return;
  154. }
  155. // set motor update speed
  156. if (on_off) {
  157. uart->write("#MBS,3\r\n"); // send request to spin motor at 4.5hz
  158. } else {
  159. uart->write("#MBS,0\r\n"); // send request to stop motor
  160. }
  161. // request update motor speed
  162. uart->write("?MBS\r\n");
  163. _last_request_type = RequestType_MotorSpeed;
  164. _last_request_ms = AP_HAL::millis();
  165. }
  166. // set spin direction of motor
  167. void AP_Proximity_LightWareSF40C::set_motor_direction()
  168. {
  169. // exit immediately if no uart
  170. if (uart == nullptr) {
  171. return;
  172. }
  173. // set motor update speed
  174. if (frontend.get_orientation(state.instance) == 0) {
  175. uart->write("#MBD,0\r\n"); // spin clockwise
  176. } else {
  177. uart->write("#MBD,1\r\n"); // spin counter clockwise
  178. }
  179. // request update on motor direction
  180. uart->write("?MBD\r\n");
  181. _last_request_type = RequestType_MotorDirection;
  182. _last_request_ms = AP_HAL::millis();
  183. }
  184. // set forward direction (to allow rotating lidar)
  185. void AP_Proximity_LightWareSF40C::set_forward_direction()
  186. {
  187. // exit immediately if no uart
  188. if (uart == nullptr) {
  189. return;
  190. }
  191. // set forward direction
  192. char request_str[15];
  193. int16_t yaw_corr = frontend.get_yaw_correction(state.instance);
  194. yaw_corr = constrain_int16(yaw_corr, -999, 999);
  195. snprintf(request_str, sizeof(request_str), "#MBF,%d\r\n", yaw_corr);
  196. uart->write(request_str);
  197. // request update on motor direction
  198. uart->write("?MBF\r\n");
  199. _last_request_type = RequestType_ForwardDirection;
  200. _last_request_ms = AP_HAL::millis();
  201. }
  202. // request new data if required
  203. void AP_Proximity_LightWareSF40C::request_new_data()
  204. {
  205. if (uart == nullptr) {
  206. return;
  207. }
  208. // after timeout assume no reply will ever come
  209. uint32_t now = AP_HAL::millis();
  210. if ((_last_request_type != RequestType_None) && ((now - _last_request_ms) > PROXIMITY_SF40C_TIMEOUT_MS)) {
  211. _last_request_type = RequestType_None;
  212. _last_request_ms = 0;
  213. }
  214. // if we are not waiting for a reply, ask for something
  215. if (_last_request_type == RequestType_None) {
  216. _request_count++;
  217. if (_request_count >= 5) {
  218. send_request_for_health();
  219. _request_count = 0;
  220. } else {
  221. // request new distance measurement
  222. send_request_for_distance();
  223. }
  224. _last_request_ms = now;
  225. }
  226. }
  227. // send request for sensor health
  228. void AP_Proximity_LightWareSF40C::send_request_for_health()
  229. {
  230. if (uart == nullptr) {
  231. return;
  232. }
  233. uart->write("?GS\r\n");
  234. _last_request_type = RequestType_Health;
  235. _last_request_ms = AP_HAL::millis();
  236. }
  237. // send request for distance from the next sector
  238. bool AP_Proximity_LightWareSF40C::send_request_for_distance()
  239. {
  240. if (uart == nullptr) {
  241. return false;
  242. }
  243. // increment sector
  244. _last_sector++;
  245. if (_last_sector >= _num_sectors) {
  246. _last_sector = 0;
  247. }
  248. // prepare request
  249. char request_str[16];
  250. snprintf(request_str, sizeof(request_str), "?TS,%u,%u\r\n",
  251. MIN(_sector_width_deg[_last_sector], 999),
  252. MIN(_sector_middle_deg[_last_sector], 999));
  253. uart->write(request_str);
  254. // record request for distance
  255. _last_request_type = RequestType_DistanceMeasurement;
  256. _last_request_ms = AP_HAL::millis();
  257. return true;
  258. }
  259. // check for replies from sensor, returns true if at least one message was processed
  260. bool AP_Proximity_LightWareSF40C::check_for_reply()
  261. {
  262. if (uart == nullptr) {
  263. return false;
  264. }
  265. // read any available lines from the lidar
  266. // if CR (i.e. \r), LF (\n) it means we have received a full packet so send for processing
  267. // lines starting with # are ignored because this is the echo of a set-motor request which has no reply
  268. // lines starting with ? are the echo back of our distance request followed by the sensed distance
  269. // distance data appears after a <space>
  270. // distance data is comma separated so we put into separate elements (i.e. <space>angle,distance)
  271. uint16_t count = 0;
  272. int16_t nbytes = uart->available();
  273. while (nbytes-- > 0) {
  274. char c = uart->read();
  275. // check for end of packet
  276. if (c == '\r' || c == '\n') {
  277. if ((element_len[0] > 0)) {
  278. if (process_reply()) {
  279. count++;
  280. }
  281. }
  282. // clear buffers after processing
  283. clear_buffers();
  284. ignore_reply = false;
  285. wait_for_space = false;
  286. // if message starts with # ignore it
  287. } else if (c == '#' || ignore_reply) {
  288. ignore_reply = true;
  289. // if waiting for <space>
  290. } else if (c == '?') {
  291. wait_for_space = true;
  292. } else if (wait_for_space) {
  293. if (c == ' ') {
  294. wait_for_space = false;
  295. }
  296. // if comma, move onto filling in 2nd element
  297. } else if (c == ',') {
  298. if ((element_num == 0) && (element_len[0] > 0)) {
  299. element_num++;
  300. } else {
  301. // don't support 3rd element so clear buffers
  302. clear_buffers();
  303. ignore_reply = true;
  304. }
  305. // if part of a number, add to element buffer
  306. } else if (isdigit(c) || c == '.' || c == '-') {
  307. element_buf[element_num][element_len[element_num]] = c;
  308. element_len[element_num]++;
  309. if (element_len[element_num] >= sizeof(element_buf[element_num])-1) {
  310. // too long, discard the line
  311. clear_buffers();
  312. ignore_reply = true;
  313. }
  314. }
  315. }
  316. return (count > 0);
  317. }
  318. // process reply
  319. bool AP_Proximity_LightWareSF40C::process_reply()
  320. {
  321. if (uart == nullptr) {
  322. return false;
  323. }
  324. bool success = false;
  325. switch (_last_request_type) {
  326. case RequestType_None:
  327. break;
  328. case RequestType_Health:
  329. // expect result in the form "0xhhhh"
  330. if (element_len[0] > 0) {
  331. long int result = strtol(element_buf[0], nullptr, 16);
  332. if (result > 0) {
  333. _sensor_status.value = result;
  334. success = true;
  335. }
  336. }
  337. break;
  338. case RequestType_MotorSpeed:
  339. _motor_speed = atoi(element_buf[0]);
  340. success = true;
  341. break;
  342. case RequestType_MotorDirection:
  343. _motor_direction = atoi(element_buf[0]);
  344. success = true;
  345. break;
  346. case RequestType_ForwardDirection:
  347. _forward_direction = atoi(element_buf[0]);
  348. success = true;
  349. break;
  350. case RequestType_DistanceMeasurement:
  351. {
  352. float angle_deg = (float)atof(element_buf[0]);
  353. float distance_m = (float)atof(element_buf[1]);
  354. uint8_t sector;
  355. if (convert_angle_to_sector(angle_deg, sector)) {
  356. _angle[sector] = angle_deg;
  357. _distance[sector] = distance_m;
  358. _distance_valid[sector] = is_positive(distance_m);
  359. _last_distance_received_ms = AP_HAL::millis();
  360. success = true;
  361. // update boundary used for avoidance
  362. update_boundary_for_sector(sector, true);
  363. }
  364. break;
  365. }
  366. default:
  367. break;
  368. }
  369. // mark request as cleared
  370. if (success) {
  371. _last_request_type = RequestType_None;
  372. }
  373. return success;
  374. }
  375. // clear buffers ahead of processing next message
  376. void AP_Proximity_LightWareSF40C::clear_buffers()
  377. {
  378. element_len[0] = 0;
  379. element_len[1] = 0;
  380. element_num = 0;
  381. memset(element_buf, 0, sizeof(element_buf));
  382. }