AP_GPS_UAVCAN.cpp 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282
  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. // UAVCAN GPS driver
  15. //
  16. #include <AP_HAL/AP_HAL.h>
  17. #if HAL_WITH_UAVCAN
  18. #include "AP_GPS_UAVCAN.h"
  19. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  20. #include <AP_UAVCAN/AP_UAVCAN.h>
  21. #include <uavcan/equipment/gnss/Fix.hpp>
  22. #include <uavcan/equipment/gnss/Auxiliary.hpp>
  23. extern const AP_HAL::HAL& hal;
  24. #define debug_gps_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { printf(fmt, ##args); }} while (0)
  25. UC_REGISTRY_BINDER(FixCb, uavcan::equipment::gnss::Fix);
  26. UC_REGISTRY_BINDER(AuxCb, uavcan::equipment::gnss::Auxiliary);
  27. AP_GPS_UAVCAN::DetectedModules AP_GPS_UAVCAN::_detected_modules[] = {0};
  28. HAL_Semaphore AP_GPS_UAVCAN::_sem_registry;
  29. // Member Methods
  30. AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state) :
  31. AP_GPS_Backend(_gps, _state, nullptr)
  32. {}
  33. AP_GPS_UAVCAN::~AP_GPS_UAVCAN()
  34. {
  35. WITH_SEMAPHORE(_sem_registry);
  36. _detected_modules[_detected_module].driver = nullptr;
  37. }
  38. void AP_GPS_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
  39. {
  40. if (ap_uavcan == nullptr) {
  41. return;
  42. }
  43. auto* node = ap_uavcan->get_node();
  44. uavcan::Subscriber<uavcan::equipment::gnss::Fix, FixCb> *gnss_fix;
  45. gnss_fix = new uavcan::Subscriber<uavcan::equipment::gnss::Fix, FixCb>(*node);
  46. const int gnss_fix_start_res = gnss_fix->start(FixCb(ap_uavcan, &handle_fix_msg_trampoline));
  47. if (gnss_fix_start_res < 0) {
  48. AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r");
  49. return;
  50. }
  51. uavcan::Subscriber<uavcan::equipment::gnss::Auxiliary, AuxCb> *gnss_aux;
  52. gnss_aux = new uavcan::Subscriber<uavcan::equipment::gnss::Auxiliary, AuxCb>(*node);
  53. const int gnss_aux_start_res = gnss_aux->start(AuxCb(ap_uavcan, &handle_aux_msg_trampoline));
  54. if (gnss_aux_start_res < 0) {
  55. AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r");
  56. return;
  57. }
  58. }
  59. AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state)
  60. {
  61. WITH_SEMAPHORE(_sem_registry);
  62. AP_GPS_UAVCAN* backend = nullptr;
  63. for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
  64. if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) {
  65. backend = new AP_GPS_UAVCAN(_gps, _state);
  66. if (backend == nullptr) {
  67. debug_gps_uavcan(2,
  68. _detected_modules[i].ap_uavcan->get_driver_index(),
  69. "Failed to register UAVCAN GPS Node %d on Bus %d\n",
  70. _detected_modules[i].node_id,
  71. _detected_modules[i].ap_uavcan->get_driver_index());
  72. } else {
  73. _detected_modules[i].driver = backend;
  74. backend->_detected_module = i;
  75. debug_gps_uavcan(2,
  76. _detected_modules[i].ap_uavcan->get_driver_index(),
  77. "Registered UAVCAN GPS Node %d on Bus %d\n",
  78. _detected_modules[i].node_id,
  79. _detected_modules[i].ap_uavcan->get_driver_index());
  80. }
  81. break;
  82. }
  83. }
  84. return backend;
  85. }
  86. AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id)
  87. {
  88. if (ap_uavcan == nullptr) {
  89. return nullptr;
  90. }
  91. for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
  92. if (_detected_modules[i].driver != nullptr &&
  93. _detected_modules[i].ap_uavcan == ap_uavcan &&
  94. _detected_modules[i].node_id == node_id) {
  95. return _detected_modules[i].driver;
  96. }
  97. }
  98. bool already_detected = false;
  99. // Check if there's an empty spot for possible registeration
  100. for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
  101. if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) {
  102. // Already Detected
  103. already_detected = true;
  104. break;
  105. }
  106. }
  107. if (!already_detected) {
  108. for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
  109. if (_detected_modules[i].ap_uavcan == nullptr) {
  110. _detected_modules[i].ap_uavcan = ap_uavcan;
  111. _detected_modules[i].node_id = node_id;
  112. break;
  113. }
  114. }
  115. }
  116. return nullptr;
  117. }
  118. void AP_GPS_UAVCAN::handle_fix_msg(const FixCb &cb)
  119. {
  120. bool process = false;
  121. WITH_SEMAPHORE(sem);
  122. if (cb.msg->status == uavcan::equipment::gnss::Fix::STATUS_NO_FIX) {
  123. interim_state.status = AP_GPS::GPS_Status::NO_FIX;
  124. } else {
  125. if (cb.msg->status == uavcan::equipment::gnss::Fix::STATUS_TIME_ONLY) {
  126. interim_state.status = AP_GPS::GPS_Status::NO_FIX;
  127. } else if (cb.msg->status == uavcan::equipment::gnss::Fix::STATUS_2D_FIX) {
  128. interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_2D;
  129. process = true;
  130. } else if (cb.msg->status == uavcan::equipment::gnss::Fix::STATUS_3D_FIX) {
  131. interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D;
  132. process = true;
  133. }
  134. if (cb.msg->gnss_time_standard == uavcan::equipment::gnss::Fix::GNSS_TIME_STANDARD_UTC) {
  135. uint64_t epoch_ms = uavcan::UtcTime(cb.msg->gnss_timestamp).toUSec();
  136. epoch_ms /= 1000;
  137. uint64_t gps_ms = epoch_ms - UNIX_OFFSET_MSEC;
  138. interim_state.time_week = (uint16_t)(gps_ms / AP_MSEC_PER_WEEK);
  139. interim_state.time_week_ms = (uint32_t)(gps_ms - (interim_state.time_week) * AP_MSEC_PER_WEEK);
  140. }
  141. }
  142. if (process) {
  143. Location loc = { };
  144. loc.lat = cb.msg->latitude_deg_1e8 / 10;
  145. loc.lng = cb.msg->longitude_deg_1e8 / 10;
  146. loc.alt = cb.msg->height_msl_mm / 10;
  147. interim_state.location = loc;
  148. if (!uavcan::isNaN(cb.msg->ned_velocity[0])) {
  149. Vector3f vel(cb.msg->ned_velocity[0], cb.msg->ned_velocity[1], cb.msg->ned_velocity[2]);
  150. interim_state.velocity = vel;
  151. interim_state.ground_speed = norm(vel.x, vel.y);
  152. interim_state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x)));
  153. interim_state.have_vertical_velocity = true;
  154. } else {
  155. interim_state.have_vertical_velocity = false;
  156. }
  157. float pos_cov[9];
  158. cb.msg->position_covariance.unpackSquareMatrix(pos_cov);
  159. if (!uavcan::isNaN(pos_cov[8])) {
  160. if (pos_cov[8] > 0) {
  161. interim_state.vertical_accuracy = sqrtf(pos_cov[8]);
  162. interim_state.have_vertical_accuracy = true;
  163. } else {
  164. interim_state.have_vertical_accuracy = false;
  165. }
  166. } else {
  167. interim_state.have_vertical_accuracy = false;
  168. }
  169. const float horizontal_pos_variance = MAX(pos_cov[0], pos_cov[4]);
  170. if (!uavcan::isNaN(horizontal_pos_variance)) {
  171. if (horizontal_pos_variance > 0) {
  172. interim_state.horizontal_accuracy = sqrtf(horizontal_pos_variance);
  173. interim_state.have_horizontal_accuracy = true;
  174. } else {
  175. interim_state.have_horizontal_accuracy = false;
  176. }
  177. } else {
  178. interim_state.have_horizontal_accuracy = false;
  179. }
  180. float vel_cov[9];
  181. cb.msg->velocity_covariance.unpackSquareMatrix(vel_cov);
  182. if (!uavcan::isNaN(vel_cov[0])) {
  183. interim_state.speed_accuracy = sqrtf((vel_cov[0] + vel_cov[4] + vel_cov[8]) / 3.0);
  184. interim_state.have_speed_accuracy = true;
  185. } else {
  186. interim_state.have_speed_accuracy = false;
  187. }
  188. interim_state.num_sats = cb.msg->sats_used;
  189. } else {
  190. interim_state.have_vertical_velocity = false;
  191. interim_state.have_vertical_accuracy = false;
  192. interim_state.have_horizontal_accuracy = false;
  193. interim_state.have_speed_accuracy = false;
  194. interim_state.num_sats = 0;
  195. }
  196. interim_state.last_gps_time_ms = AP_HAL::millis();
  197. _new_data = true;
  198. }
  199. void AP_GPS_UAVCAN::handle_aux_msg(const AuxCb &cb)
  200. {
  201. WITH_SEMAPHORE(sem);
  202. if (!uavcan::isNaN(cb.msg->hdop)) {
  203. interim_state.hdop = cb.msg->hdop * 100.0;
  204. }
  205. if (!uavcan::isNaN(cb.msg->vdop)) {
  206. interim_state.vdop = cb.msg->vdop * 100.0;
  207. }
  208. }
  209. void AP_GPS_UAVCAN::handle_fix_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const FixCb &cb)
  210. {
  211. WITH_SEMAPHORE(_sem_registry);
  212. AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id);
  213. if (driver != nullptr) {
  214. driver->handle_fix_msg(cb);
  215. }
  216. }
  217. void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AuxCb &cb)
  218. {
  219. WITH_SEMAPHORE(_sem_registry);
  220. AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id);
  221. if (driver != nullptr) {
  222. driver->handle_aux_msg(cb);
  223. }
  224. }
  225. // Consume new data and mark it received
  226. bool AP_GPS_UAVCAN::read(void)
  227. {
  228. WITH_SEMAPHORE(sem);
  229. if (_new_data) {
  230. _new_data = false;
  231. state = interim_state;
  232. return true;
  233. }
  234. return false;
  235. }
  236. #endif // HAL_WITH_UAVCAN