AP_RangeFinder_UAVCAN.cpp 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181
  1. #include <AP_HAL/AP_HAL.h>
  2. #if HAL_WITH_UAVCAN
  3. #include "AP_RangeFinder_UAVCAN.h"
  4. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  5. #include <AP_UAVCAN/AP_UAVCAN.h>
  6. #include <uavcan/equipment/range_sensor/Measurement.hpp>
  7. extern const AP_HAL::HAL& hal;
  8. #define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0)
  9. //UAVCAN Frontend Registry Binder
  10. UC_REGISTRY_BINDER(MeasurementCb, uavcan::equipment::range_sensor::Measurement);
  11. /*
  12. constructor - registers instance at top RangeFinder driver
  13. */
  14. AP_RangeFinder_UAVCAN::AP_RangeFinder_UAVCAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
  15. AP_RangeFinder_Backend(_state, _params)
  16. {}
  17. //links the rangefinder uavcan message to this backend
  18. void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
  19. {
  20. if (ap_uavcan == nullptr) {
  21. return;
  22. }
  23. auto* node = ap_uavcan->get_node();
  24. uavcan::Subscriber<uavcan::equipment::range_sensor::Measurement, MeasurementCb> *measurement_listener;
  25. measurement_listener = new uavcan::Subscriber<uavcan::equipment::range_sensor::Measurement, MeasurementCb>(*node);
  26. // Register method to handle incoming RangeFinder measurement
  27. const int measurement_listener_res = measurement_listener->start(MeasurementCb(ap_uavcan, &handle_measurement));
  28. if (measurement_listener_res < 0) {
  29. AP_HAL::panic("UAVCAN RangeFinder subscriber start problem\n\r");
  30. return;
  31. }
  32. }
  33. //Method to find the backend relating to the node id
  34. AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new)
  35. {
  36. if (ap_uavcan == nullptr) {
  37. return nullptr;
  38. }
  39. AP_RangeFinder_UAVCAN* driver = nullptr;
  40. //Scan through the Rangefinder params to find UAVCAN RFND with matching address.
  41. for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
  42. if (AP::rangefinder()->params[i].type == RangeFinder::RangeFinder_TYPE_UAVCAN &&
  43. AP::rangefinder()->params[i].address == address) {
  44. driver = (AP_RangeFinder_UAVCAN*)AP::rangefinder()->drivers[i];
  45. }
  46. //Double check if the driver was initialised as UAVCAN Type
  47. if (driver != nullptr && (driver->_backend_type == RangeFinder::RangeFinder_TYPE_UAVCAN)) {
  48. if (driver->_ap_uavcan == ap_uavcan &&
  49. driver->_node_id == node_id) {
  50. return driver;
  51. } else {
  52. //we found a possible duplicate addressed sensor
  53. //we return nothing in such scenario
  54. return nullptr;
  55. }
  56. }
  57. }
  58. if (create_new) {
  59. for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
  60. if (AP::rangefinder()->params[i].type == RangeFinder::RangeFinder_TYPE_UAVCAN &&
  61. AP::rangefinder()->params[i].address == address) {
  62. if (AP::rangefinder()->drivers[i] != nullptr) {
  63. //we probably initialised this driver as something else, reboot is required for setting
  64. //it up as UAVCAN type
  65. return nullptr;
  66. }
  67. AP::rangefinder()->drivers[i] = new AP_RangeFinder_UAVCAN(AP::rangefinder()->state[i], AP::rangefinder()->params[i]);
  68. driver = (AP_RangeFinder_UAVCAN*)AP::rangefinder()->drivers[i];
  69. if (driver == nullptr) {
  70. break;
  71. }
  72. AP::rangefinder()->num_instances = MAX(i+1, AP::rangefinder()->num_instances);
  73. //Assign node id and respective uavcan driver, for identification
  74. if (driver->_ap_uavcan == nullptr) {
  75. driver->_ap_uavcan = ap_uavcan;
  76. driver->_node_id = node_id;
  77. break;
  78. }
  79. }
  80. }
  81. }
  82. return driver;
  83. }
  84. //Called from frontend to update with the readings received by handler
  85. void AP_RangeFinder_UAVCAN::update()
  86. {
  87. WITH_SEMAPHORE(_sem);
  88. if ((AP_HAL::millis() - _last_reading_ms) > 500) {
  89. //if data is older than 500ms, report NoData
  90. set_status(RangeFinder::RangeFinder_NoData);
  91. } else if (_status == RangeFinder::RangeFinder_Good && new_data) {
  92. //copy over states
  93. state.distance_cm = _distance_cm;
  94. state.last_reading_ms = _last_reading_ms;
  95. update_status();
  96. new_data = false;
  97. } else if (_status != RangeFinder::RangeFinder_Good) {
  98. //handle additional states received by measurement handler
  99. set_status(_status);
  100. }
  101. }
  102. //RangeFinder message handler
  103. void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MeasurementCb &cb)
  104. {
  105. //fetch the matching uavcan driver, node id and sensor id backend instance
  106. AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, cb.msg->sensor_id, true);
  107. if (driver == nullptr) {
  108. return;
  109. }
  110. WITH_SEMAPHORE(driver->_sem);
  111. switch (cb.msg->reading_type) {
  112. case uavcan::equipment::range_sensor::Measurement::READING_TYPE_VALID_RANGE:
  113. {
  114. //update the states in backend instance
  115. driver->_distance_cm = cb.msg->range*100.0f;
  116. driver->_last_reading_ms = AP_HAL::millis();
  117. driver->_status = RangeFinder::RangeFinder_Good;
  118. driver->new_data = true;
  119. break;
  120. }
  121. //Additional states supported by RFND message
  122. case uavcan::equipment::range_sensor::Measurement::READING_TYPE_TOO_CLOSE:
  123. {
  124. driver->_last_reading_ms = AP_HAL::millis();
  125. driver->_status = RangeFinder::RangeFinder_OutOfRangeLow;
  126. break;
  127. }
  128. case uavcan::equipment::range_sensor::Measurement::READING_TYPE_TOO_FAR:
  129. {
  130. driver->_last_reading_ms = AP_HAL::millis();
  131. driver->_status = RangeFinder::RangeFinder_OutOfRangeHigh;
  132. break;
  133. }
  134. default:
  135. {
  136. break;
  137. }
  138. }
  139. //copy over the sensor type of Rangefinder
  140. switch (cb.msg->sensor_type) {
  141. case uavcan::equipment::range_sensor::Measurement::SENSOR_TYPE_SONAR:
  142. {
  143. driver->_sensor_type = MAV_DISTANCE_SENSOR_ULTRASOUND;
  144. break;
  145. }
  146. case uavcan::equipment::range_sensor::Measurement::SENSOR_TYPE_LIDAR:
  147. {
  148. driver->_sensor_type = MAV_DISTANCE_SENSOR_LASER;
  149. break;
  150. }
  151. case uavcan::equipment::range_sensor::Measurement::SENSOR_TYPE_RADAR:
  152. {
  153. driver->_sensor_type = MAV_DISTANCE_SENSOR_RADAR;
  154. break;
  155. }
  156. default:
  157. {
  158. driver->_sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN;
  159. break;
  160. }
  161. }
  162. }
  163. #endif // HAL_WITH_UAVCAN