AP_RangeFinder_MaxsonarI2CXL.cpp 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160
  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. /*
  14. * AP_RangeFinder_MaxsonarI2CXL.cpp - Arduino Library for MaxBotix I2C XL sonar
  15. * Code by Randy Mackay. DIYDrones.com
  16. *
  17. * datasheet: http://www.maxbotix.com/documents/I2CXL-MaxSonar-EZ_Datasheet.pdf
  18. *
  19. * Sensor should be connected to the I2C port
  20. */
  21. #include "AP_RangeFinder_MaxsonarI2CXL.h"
  22. #include <utility>
  23. #include <AP_HAL/AP_HAL.h>
  24. #include <AP_HAL/utility/sparse-endian.h>
  25. extern const AP_HAL::HAL& hal;
  26. /*
  27. The constructor also initializes the rangefinder. Note that this
  28. constructor is not called until detect() returns true, so we
  29. already know that we should setup the rangefinder
  30. */
  31. AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state,
  32. AP_RangeFinder_Params &_params,
  33. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  34. : AP_RangeFinder_Backend(_state, _params)
  35. , _dev(std::move(dev))
  36. {
  37. }
  38. /*
  39. detect if a Maxbotix rangefinder is connected. We'll detect by
  40. trying to take a reading on I2C. If we get a result the sensor is
  41. there.
  42. */
  43. AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeFinder_State &_state,
  44. AP_RangeFinder_Params &_params,
  45. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  46. {
  47. if (!dev) {
  48. return nullptr;
  49. }
  50. AP_RangeFinder_MaxsonarI2CXL *sensor
  51. = new AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev));
  52. if (!sensor) {
  53. return nullptr;
  54. }
  55. if (!sensor->_init()) {
  56. delete sensor;
  57. return nullptr;
  58. }
  59. return sensor;
  60. }
  61. /*
  62. initialise sensor
  63. */
  64. bool AP_RangeFinder_MaxsonarI2CXL::_init(void)
  65. {
  66. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  67. return false;
  68. }
  69. if (!start_reading()) {
  70. _dev->get_semaphore()->give();
  71. return false;
  72. }
  73. // give time for the sensor to process the request
  74. hal.scheduler->delay(100);
  75. uint16_t reading_cm;
  76. if (!get_reading(reading_cm)) {
  77. _dev->get_semaphore()->give();
  78. return false;
  79. }
  80. _dev->get_semaphore()->give();
  81. _dev->register_periodic_callback(100000,
  82. FUNCTOR_BIND_MEMBER(&AP_RangeFinder_MaxsonarI2CXL::_timer, void));
  83. return true;
  84. }
  85. // start_reading() - ask sensor to make a range reading
  86. bool AP_RangeFinder_MaxsonarI2CXL::start_reading()
  87. {
  88. uint8_t cmd = AP_RANGE_FINDER_MAXSONARI2CXL_COMMAND_TAKE_RANGE_READING;
  89. // send command to take reading
  90. return _dev->transfer(&cmd, sizeof(cmd), nullptr, 0);
  91. }
  92. // read - return last value measured by sensor
  93. bool AP_RangeFinder_MaxsonarI2CXL::get_reading(uint16_t &reading_cm)
  94. {
  95. be16_t val;
  96. // take range reading and read back results
  97. bool ret = _dev->transfer(nullptr, 0, (uint8_t *) &val, sizeof(val));
  98. if (ret) {
  99. // combine results into distance
  100. reading_cm = be16toh(val);
  101. // trigger a new reading
  102. start_reading();
  103. }
  104. return ret;
  105. }
  106. /*
  107. timer called at 10Hz
  108. */
  109. void AP_RangeFinder_MaxsonarI2CXL::_timer(void)
  110. {
  111. uint16_t d;
  112. if (get_reading(d)) {
  113. WITH_SEMAPHORE(_sem);
  114. distance = d;
  115. new_distance = true;
  116. state.last_reading_ms = AP_HAL::millis();
  117. }
  118. }
  119. /*
  120. update the state of the sensor
  121. */
  122. void AP_RangeFinder_MaxsonarI2CXL::update(void)
  123. {
  124. WITH_SEMAPHORE(_sem);
  125. if (new_distance) {
  126. state.distance_cm = distance;
  127. new_distance = false;
  128. update_status();
  129. } else if (AP_HAL::millis() - state.last_reading_ms > 300) {
  130. // if no updates for 0.3 seconds set no-data
  131. set_status(RangeFinder::RangeFinder_NoData);
  132. }
  133. }