UAVCAN_sniffer.cpp 8.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322
  1. /*
  2. simple UAVCAN network sniffer as an ArduPilot firmware
  3. */
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_HAL/AP_HAL.h>
  6. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && HAL_WITH_UAVCAN
  7. #include <AP_HAL/CAN.h>
  8. #include <AP_HAL/Semaphores.h>
  9. #include <AP_HAL_ChibiOS/CAN.h>
  10. #include <AP_UAVCAN/AP_UAVCAN.h>
  11. #include <uavcan/uavcan.hpp>
  12. #include <uavcan/helpers/heap_based_pool_allocator.hpp>
  13. #include <uavcan/equipment/gnss/Fix.hpp>
  14. #include <uavcan/equipment/gnss/Auxiliary.hpp>
  15. #include <uavcan/equipment/ahrs/MagneticFieldStrength.hpp>
  16. #include <uavcan/equipment/ahrs/MagneticFieldStrength2.hpp>
  17. #include <uavcan/equipment/air_data/StaticPressure.hpp>
  18. #include <uavcan/equipment/air_data/StaticTemperature.hpp>
  19. #include <uavcan/equipment/actuator/ArrayCommand.hpp>
  20. #include <uavcan/equipment/actuator/Command.hpp>
  21. #include <uavcan/equipment/actuator/Status.hpp>
  22. #include <uavcan/equipment/esc/RawCommand.hpp>
  23. #include <uavcan/equipment/indication/LightsCommand.hpp>
  24. #include <uavcan/equipment/indication/SingleLightCommand.hpp>
  25. #include <uavcan/equipment/indication/RGB565.hpp>
  26. #include <uavcan/equipment/power/BatteryInfo.hpp>
  27. #include <com/hex/equipment/flow/Measurement.hpp>
  28. void setup();
  29. void loop();
  30. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  31. #define UAVCAN_NODE_POOL_SIZE 8192
  32. #ifdef UAVCAN_NODE_POOL_BLOCK_SIZE
  33. #undef UAVCAN_NODE_POOL_BLOCK_SIZE
  34. #endif
  35. #define UAVCAN_NODE_POOL_BLOCK_SIZE 256
  36. #define debug_uavcan(fmt, args...) do { hal.console->printf(fmt, ##args); } while (0)
  37. class UAVCAN_sniffer {
  38. public:
  39. UAVCAN_sniffer();
  40. ~UAVCAN_sniffer();
  41. void init(void);
  42. void loop(void);
  43. void print_stats(void);
  44. private:
  45. uint8_t driver_index = 0;
  46. class SystemClock: public uavcan::ISystemClock, uavcan::Noncopyable {
  47. SystemClock()
  48. {
  49. }
  50. uavcan::UtcDuration utc_adjustment;
  51. virtual void adjustUtc(uavcan::UtcDuration adjustment) override
  52. {
  53. utc_adjustment = adjustment;
  54. }
  55. public:
  56. virtual uavcan::MonotonicTime getMonotonic() const override
  57. {
  58. uavcan::uint64_t usec = 0;
  59. usec = AP_HAL::micros64();
  60. return uavcan::MonotonicTime::fromUSec(usec);
  61. }
  62. virtual uavcan::UtcTime getUtc() const override
  63. {
  64. uavcan::UtcTime utc;
  65. uavcan::uint64_t usec = 0;
  66. usec = AP_HAL::micros64();
  67. utc.fromUSec(usec);
  68. utc += utc_adjustment;
  69. return utc;
  70. }
  71. static SystemClock& instance()
  72. {
  73. static SystemClock inst;
  74. return inst;
  75. }
  76. };
  77. uavcan::Node<0> *_node;
  78. uavcan::ISystemClock& get_system_clock();
  79. // This will be needed to implement if UAVCAN is used with multithreading
  80. // Such cases will be firmware update, etc.
  81. class RaiiSynchronizer {
  82. public:
  83. RaiiSynchronizer()
  84. {
  85. }
  86. ~RaiiSynchronizer()
  87. {
  88. }
  89. };
  90. uavcan::HeapBasedPoolAllocator<UAVCAN_NODE_POOL_BLOCK_SIZE, UAVCAN_sniffer::RaiiSynchronizer> _node_allocator;
  91. };
  92. static struct {
  93. const char *msg_name;
  94. uint32_t count;
  95. } counters[100];
  96. static void count_msg(const char *name)
  97. {
  98. for (uint16_t i=0; i<ARRAY_SIZE(counters); i++) {
  99. if (counters[i].msg_name == name) {
  100. counters[i].count++;
  101. break;
  102. }
  103. if (counters[i].msg_name == nullptr) {
  104. counters[i].msg_name = name;
  105. counters[i].count++;
  106. break;
  107. }
  108. }
  109. }
  110. #define MSG_CB(mtype, cbname) \
  111. static void cb_ ## cbname(const uavcan::ReceivedDataStructure<mtype>& msg) { count_msg(msg.getDataTypeFullName()); }
  112. MSG_CB(uavcan::protocol::NodeStatus, NodeStatus)
  113. MSG_CB(uavcan::equipment::gnss::Fix, Fix)
  114. MSG_CB(uavcan::equipment::gnss::Auxiliary, Auxiliary)
  115. MSG_CB(uavcan::equipment::ahrs::MagneticFieldStrength, MagneticFieldStrength)
  116. MSG_CB(uavcan::equipment::ahrs::MagneticFieldStrength2, MagneticFieldStrength2);
  117. MSG_CB(uavcan::equipment::air_data::StaticPressure, StaticPressure)
  118. MSG_CB(uavcan::equipment::air_data::StaticTemperature, StaticTemperature)
  119. MSG_CB(uavcan::equipment::power::BatteryInfo, BatteryInfo);
  120. MSG_CB(uavcan::equipment::actuator::ArrayCommand, ArrayCommand)
  121. MSG_CB(uavcan::equipment::esc::RawCommand, RawCommand)
  122. MSG_CB(uavcan::equipment::indication::LightsCommand, LightsCommand);
  123. MSG_CB(com::hex::equipment::flow::Measurement, Measurement);
  124. void UAVCAN_sniffer::init(void)
  125. {
  126. uint8_t interface = 0;
  127. AP_HAL::CANManager* can_mgr = new ChibiOS::CANManager;
  128. if (can_mgr == nullptr) {
  129. AP_HAL::panic("Couldn't allocate CANManager, something is very wrong");
  130. }
  131. const_cast <AP_HAL::HAL&> (hal).can_mgr[driver_index] = can_mgr;
  132. can_mgr->begin(1000000, interface);
  133. can_mgr->initialized(true);
  134. if (!can_mgr->is_initialized()) {
  135. debug_uavcan("Can not initialised\n");
  136. return;
  137. }
  138. uavcan::ICanDriver* driver = can_mgr->get_driver();
  139. if (driver == nullptr) {
  140. return;
  141. }
  142. _node = new uavcan::Node<0>(*driver, get_system_clock(), _node_allocator);
  143. if (_node == nullptr) {
  144. return;
  145. }
  146. if (_node->isStarted()) {
  147. return;
  148. }
  149. uavcan::NodeID self_node_id(9);
  150. _node->setNodeID(self_node_id);
  151. char ndname[20];
  152. snprintf(ndname, sizeof(ndname), "org.ardupilot:%u", driver_index);
  153. uavcan::NodeStatusProvider::NodeName name(ndname);
  154. _node->setName(name);
  155. uavcan::protocol::SoftwareVersion sw_version; // Standard type uavcan.protocol.SoftwareVersion
  156. sw_version.major = AP_UAVCAN_SW_VERS_MAJOR;
  157. sw_version.minor = AP_UAVCAN_SW_VERS_MINOR;
  158. _node->setSoftwareVersion(sw_version);
  159. uavcan::protocol::HardwareVersion hw_version; // Standard type uavcan.protocol.HardwareVersion
  160. hw_version.major = AP_UAVCAN_HW_VERS_MAJOR;
  161. hw_version.minor = AP_UAVCAN_HW_VERS_MINOR;
  162. _node->setHardwareVersion(hw_version);
  163. int start_res = _node->start();
  164. if (start_res < 0) {
  165. debug_uavcan("UAVCAN: node start problem\n\r");
  166. return;
  167. }
  168. #define START_CB(mtype, cbname) (new uavcan::Subscriber<mtype>(*_node))->start(cb_ ## cbname)
  169. START_CB(uavcan::protocol::NodeStatus, NodeStatus);
  170. START_CB(uavcan::equipment::gnss::Fix, Fix);
  171. START_CB(uavcan::equipment::gnss::Auxiliary, Auxiliary);
  172. START_CB(uavcan::equipment::ahrs::MagneticFieldStrength, MagneticFieldStrength);
  173. START_CB(uavcan::equipment::ahrs::MagneticFieldStrength2, MagneticFieldStrength2);
  174. START_CB(uavcan::equipment::air_data::StaticPressure, StaticPressure);
  175. START_CB(uavcan::equipment::air_data::StaticTemperature, StaticTemperature);
  176. START_CB(uavcan::equipment::power::BatteryInfo, BatteryInfo);
  177. START_CB(uavcan::equipment::actuator::ArrayCommand, ArrayCommand);
  178. START_CB(uavcan::equipment::esc::RawCommand, RawCommand);
  179. START_CB(uavcan::equipment::indication::LightsCommand, LightsCommand);
  180. START_CB(com::hex::equipment::flow::Measurement, Measurement);
  181. /*
  182. * Informing other nodes that we're ready to work.
  183. * Default mode is INITIALIZING.
  184. */
  185. _node->setModeOperational();
  186. debug_uavcan("UAVCAN: init done\n\r");
  187. }
  188. uavcan::ISystemClock & UAVCAN_sniffer::get_system_clock()
  189. {
  190. return SystemClock::instance();
  191. }
  192. void UAVCAN_sniffer::loop(void)
  193. {
  194. if (_node == nullptr) {
  195. return;
  196. }
  197. _node->spin(uavcan::MonotonicDuration::fromMSec(1));
  198. }
  199. void UAVCAN_sniffer::print_stats(void)
  200. {
  201. hal.console->printf("%lu\n", AP_HAL::micros());
  202. for (uint16_t i=0;i<100;i++) {
  203. if (counters[i].msg_name == nullptr) {
  204. break;
  205. }
  206. hal.console->printf("%s: %u\n", counters[i].msg_name, unsigned(counters[i].count));
  207. counters[i].count = 0;
  208. }
  209. hal.console->printf("\n");
  210. }
  211. static UAVCAN_sniffer sniffer;
  212. UAVCAN_sniffer::UAVCAN_sniffer() :
  213. _node_allocator(UAVCAN_NODE_POOL_SIZE, UAVCAN_NODE_POOL_SIZE)
  214. {}
  215. UAVCAN_sniffer::~UAVCAN_sniffer()
  216. {
  217. }
  218. void setup(void)
  219. {
  220. hal.scheduler->delay(2000);
  221. hal.console->printf("Starting UAVCAN sniffer\n");
  222. sniffer.init();
  223. }
  224. void loop(void)
  225. {
  226. sniffer.loop();
  227. static uint32_t last_print_ms;
  228. uint32_t now = AP_HAL::millis();
  229. if (now - last_print_ms >= 1000) {
  230. last_print_ms = now;
  231. sniffer.print_stats();
  232. }
  233. // auto-reboot for --upload
  234. if (hal.console->available() > 50) {
  235. hal.console->printf("rebooting\n");
  236. while (hal.console->available()) {
  237. hal.console->read();
  238. }
  239. hal.scheduler->reboot(false);
  240. }
  241. while (hal.console->available()) {
  242. hal.console->read();
  243. }
  244. }
  245. AP_HAL_MAIN();
  246. #else
  247. #include <stdio.h>
  248. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  249. static void loop() { }
  250. static void setup()
  251. {
  252. printf("Board not currently supported\n");
  253. }
  254. AP_HAL_MAIN();
  255. #endif