AP_Airspeed_UAVCAN.cpp 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156
  1. #include <AP_HAL/AP_HAL.h>
  2. #if HAL_WITH_UAVCAN
  3. #include "AP_Airspeed_UAVCAN.h"
  4. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  5. #include <AP_UAVCAN/AP_UAVCAN.h>
  6. #include <uavcan/equipment/air_data/RawAirData.hpp>
  7. extern const AP_HAL::HAL& hal;
  8. #define debug_airspeed_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { printf(fmt, ##args); }} while (0)
  9. // UAVCAN Frontend Registry Binder
  10. UC_REGISTRY_BINDER(AirspeedCb, uavcan::equipment::air_data::RawAirData);
  11. AP_Airspeed_UAVCAN::DetectedModules AP_Airspeed_UAVCAN::_detected_modules[] = {0};
  12. HAL_Semaphore AP_Airspeed_UAVCAN::_sem_registry;
  13. // constructor
  14. AP_Airspeed_UAVCAN::AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance) :
  15. AP_Airspeed_Backend(_frontend, _instance)
  16. {}
  17. void AP_Airspeed_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
  18. {
  19. if (ap_uavcan == nullptr) {
  20. return;
  21. }
  22. auto* node = ap_uavcan->get_node();
  23. uavcan::Subscriber<uavcan::equipment::air_data::RawAirData, AirspeedCb> *airspeed_listener;
  24. airspeed_listener = new uavcan::Subscriber<uavcan::equipment::air_data::RawAirData, AirspeedCb>(*node);
  25. const int airspeed_listener_res = airspeed_listener->start(AirspeedCb(ap_uavcan, &handle_airspeed));
  26. if (airspeed_listener_res < 0) {
  27. AP_HAL::panic("UAVCAN Airspeed subscriber start problem\n");
  28. }
  29. }
  30. AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance)
  31. {
  32. WITH_SEMAPHORE(_sem_registry);
  33. AP_Airspeed_UAVCAN* backend = nullptr;
  34. for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
  35. if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) {
  36. backend = new AP_Airspeed_UAVCAN(_frontend, _instance);
  37. if (backend == nullptr) {
  38. debug_airspeed_uavcan(2,
  39. _detected_modules[i].ap_uavcan->get_driver_index(),
  40. "Failed register UAVCAN Airspeed Node %d on Bus %d\n",
  41. _detected_modules[i].node_id,
  42. _detected_modules[i].ap_uavcan->get_driver_index());
  43. } else {
  44. _detected_modules[i].driver = backend;
  45. debug_airspeed_uavcan(2,
  46. _detected_modules[i].ap_uavcan->get_driver_index(),
  47. "Registered UAVCAN Airspeed Node %d on Bus %d\n",
  48. _detected_modules[i].node_id,
  49. _detected_modules[i].ap_uavcan->get_driver_index());
  50. }
  51. break;
  52. }
  53. }
  54. return backend;
  55. }
  56. AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id)
  57. {
  58. if (ap_uavcan == nullptr) {
  59. return nullptr;
  60. }
  61. for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
  62. if (_detected_modules[i].driver != nullptr &&
  63. _detected_modules[i].ap_uavcan == ap_uavcan &&
  64. _detected_modules[i].node_id == node_id ) {
  65. return _detected_modules[i].driver;
  66. }
  67. }
  68. bool detected = false;
  69. for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
  70. if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) {
  71. // detected
  72. detected = true;
  73. break;
  74. }
  75. }
  76. if (!detected) {
  77. for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
  78. if (_detected_modules[i].ap_uavcan == nullptr) {
  79. _detected_modules[i].ap_uavcan = ap_uavcan;
  80. _detected_modules[i].node_id = node_id;
  81. break;
  82. }
  83. }
  84. }
  85. return nullptr;
  86. }
  87. void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb)
  88. {
  89. WITH_SEMAPHORE(_sem_registry);
  90. AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id);
  91. if (driver != nullptr) {
  92. WITH_SEMAPHORE(driver->_sem_airspeed);
  93. driver->_pressure = cb.msg->differential_pressure;
  94. driver->_temperature = cb.msg->static_air_temperature - C_TO_KELVIN;
  95. driver->_last_sample_time_ms = AP_HAL::millis();
  96. }
  97. }
  98. bool AP_Airspeed_UAVCAN::init()
  99. {
  100. // always returns true
  101. return true;
  102. }
  103. bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure)
  104. {
  105. WITH_SEMAPHORE(_sem_airspeed);
  106. if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
  107. return false;
  108. }
  109. pressure = _pressure;
  110. return true;
  111. }
  112. bool AP_Airspeed_UAVCAN::get_temperature(float &temperature)
  113. {
  114. WITH_SEMAPHORE(_sem_airspeed);
  115. if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
  116. return false;
  117. }
  118. temperature = _temperature;
  119. return true;
  120. }
  121. #endif // HAL_WITH_UAVCAN