APM:Libraries
UAVCAN_sniffer.cpp
Go to the documentation of this file.
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 
7 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && HAL_WITH_UAVCAN
8 
9 #include <uavcan/uavcan.hpp>
10 
11 #include <AP_HAL/CAN.h>
12 #include <AP_HAL/Semaphores.h>
13 #include <AP_HAL_ChibiOS/CAN.h>
14 
15 #include <uavcan/helpers/heap_based_pool_allocator.hpp>
16 #include <uavcan/equipment/indication/RGB565.hpp>
17 
18 #include <uavcan/equipment/gnss/Fix.hpp>
19 #include <uavcan/equipment/gnss/Auxiliary.hpp>
20 
21 #include <uavcan/equipment/ahrs/MagneticFieldStrength.hpp>
22 #include <uavcan/equipment/ahrs/MagneticFieldStrength2.hpp>
23 #include <uavcan/equipment/air_data/StaticPressure.hpp>
24 #include <uavcan/equipment/air_data/StaticTemperature.hpp>
25 
26 #include <uavcan/equipment/actuator/ArrayCommand.hpp>
27 #include <uavcan/equipment/actuator/Command.hpp>
28 #include <uavcan/equipment/actuator/Status.hpp>
29 
30 #include <uavcan/equipment/esc/RawCommand.hpp>
31 #include <uavcan/equipment/indication/LightsCommand.hpp>
32 #include <uavcan/equipment/indication/SingleLightCommand.hpp>
33 #include <uavcan/equipment/indication/RGB565.hpp>
34 
35 #include <uavcan/equipment/power/BatteryInfo.hpp>
36 
37 void setup();
38 void loop();
39 
41 
42 #define UAVCAN_NODE_POOL_SIZE 8192
43 #define UAVCAN_NODE_POOL_BLOCK_SIZE 256
44 
45 #define debug_uavcan(level, fmt, args...) do { hal.console->printf(fmt, ##args); } while (0)
46 
47 class UAVCAN_sniffer {
48 public:
49  UAVCAN_sniffer();
50  ~UAVCAN_sniffer();
51 
52  void init(void);
53  void loop(void);
54  void print_stats(void);
55 
56 private:
57  AP_HAL::Semaphore *_led_out_sem;
58 
59  class SystemClock: public uavcan::ISystemClock, uavcan::Noncopyable {
60  SystemClock()
61  {
62  }
63 
64  uavcan::UtcDuration utc_adjustment;
65  virtual void adjustUtc(uavcan::UtcDuration adjustment)
66  {
67  utc_adjustment = adjustment;
68  }
69 
70  public:
71  virtual uavcan::MonotonicTime getMonotonic() const
72  {
73  uavcan::uint64_t usec = 0;
74  usec = AP_HAL::micros64();
75  return uavcan::MonotonicTime::fromUSec(usec);
76  }
77  virtual uavcan::UtcTime getUtc() const
78  {
79  uavcan::UtcTime utc;
80  uavcan::uint64_t usec = 0;
81  usec = AP_HAL::micros64();
82  utc.fromUSec(usec);
83  utc += utc_adjustment;
84  return utc;
85  }
86 
87  static SystemClock& instance()
88  {
89  static SystemClock inst;
90  return inst;
91  }
92  };
93 
94  uavcan::Node<0> *_node;
95 
96  uavcan::ISystemClock& get_system_clock();
97  uavcan::ICanDriver* get_can_driver();
98  uavcan::Node<0>* get_node();
99 
100  // This will be needed to implement if UAVCAN is used with multithreading
101  // Such cases will be firmware update, etc.
102  class RaiiSynchronizer {
103  public:
104  RaiiSynchronizer()
105  {
106  }
107 
108  ~RaiiSynchronizer()
109  {
110  }
111  };
112 
113  uavcan::HeapBasedPoolAllocator<UAVCAN_NODE_POOL_BLOCK_SIZE, UAVCAN_sniffer::RaiiSynchronizer> _node_allocator;
114 
115  AP_HAL::CANManager* _parent_can_mgr;
116 
117  void set_parent_can_mgr(AP_HAL::CANManager* parent_can_mgr)
118  {
119  _parent_can_mgr = parent_can_mgr;
120  }
121 };
122 
123 static struct {
124  const char *msg_name;
125  uint32_t count;
126 } counters[100];
127 
128 static void count_msg(const char *name)
129 {
130  for (uint16_t i=0; i<ARRAY_SIZE_SIMPLE(counters); i++) {
131  if (counters[i].msg_name == name) {
132  counters[i].count++;
133  break;
134  }
135  if (counters[i].msg_name == nullptr) {
136  counters[i].msg_name = name;
137  counters[i].count++;
138  break;
139  }
140  }
141 }
142 
143 #define MSG_CB(mtype, cbname) \
144  static void cb_ ## cbname(const uavcan::ReceivedDataStructure<mtype>& msg) { count_msg(msg.getDataTypeFullName()); }
145 
146 MSG_CB(uavcan::protocol::NodeStatus, NodeStatus)
147 MSG_CB(uavcan::equipment::gnss::Fix, Fix)
148 MSG_CB(uavcan::equipment::ahrs::MagneticFieldStrength, MagneticFieldStrength)
149 MSG_CB(uavcan::equipment::air_data::StaticPressure, StaticPressure)
150 MSG_CB(uavcan::equipment::air_data::StaticTemperature, StaticTemperature)
151 MSG_CB(uavcan::equipment::gnss::Auxiliary, Auxiliary)
152 MSG_CB(uavcan::equipment::actuator::ArrayCommand, ArrayCommand)
153 MSG_CB(uavcan::equipment::esc::RawCommand, RawCommand)
154 
155 void UAVCAN_sniffer::init(void)
156 {
157  uint8_t inum = 0;
158  const_cast <AP_HAL::HAL&> (hal).can_mgr[inum] = new ChibiOS::CANManager;
159  hal.can_mgr[0]->begin(1000000, inum);
160 
161  set_parent_can_mgr(hal.can_mgr[inum]);
162 
163  if (!_parent_can_mgr->is_initialized()) {
164  hal.console->printf("Can not initialised\n");
165  return;
166  }
167 
168  auto *node = get_node();
169 
170  uavcan::NodeID self_node_id(9);
171  node->setNodeID(self_node_id);
172 
173  char ndname[20];
174  snprintf(ndname, sizeof(ndname), "org.ardupilot:%u", inum);
175 
176  uavcan::NodeStatusProvider::NodeName name(ndname);
177  node->setName(name);
178 
179  uavcan::protocol::SoftwareVersion sw_version; // Standard type uavcan.protocol.SoftwareVersion
180  sw_version.major = AP_UAVCAN_SW_VERS_MAJOR;
181  sw_version.minor = AP_UAVCAN_SW_VERS_MINOR;
182  node->setSoftwareVersion(sw_version);
183 
184  uavcan::protocol::HardwareVersion hw_version; // Standard type uavcan.protocol.HardwareVersion
185 
186  hw_version.major = AP_UAVCAN_HW_VERS_MAJOR;
187  hw_version.minor = AP_UAVCAN_HW_VERS_MINOR;
188  node->setHardwareVersion(hw_version);
189 
190  const int node_start_res = node->start();
191  if (node_start_res < 0) {
192  debug_uavcan(1, "UAVCAN: node start problem\n\r");
193  }
194 
195 #define START_CB(mtype, cbname) (new uavcan::Subscriber<mtype>(*node))->start(cb_ ## cbname)
196 
197  START_CB(uavcan::protocol::NodeStatus, NodeStatus);
198  START_CB(uavcan::equipment::gnss::Fix, Fix);
199  START_CB(uavcan::equipment::ahrs::MagneticFieldStrength, MagneticFieldStrength);
200  START_CB(uavcan::equipment::air_data::StaticPressure, StaticPressure);
201  START_CB(uavcan::equipment::air_data::StaticTemperature, StaticTemperature);
202  START_CB(uavcan::equipment::gnss::Auxiliary, Auxiliary);
203  START_CB(uavcan::equipment::actuator::ArrayCommand, ArrayCommand);
204  START_CB(uavcan::equipment::esc::RawCommand, RawCommand);
205 
206  /*
207  * Informing other nodes that we're ready to work.
208  * Default mode is INITIALIZING.
209  */
210  node->setModeOperational();
211 
212  debug_uavcan(1, "UAVCAN: init done\n\r");
213 }
214 
215 uavcan::Node<0> *UAVCAN_sniffer::get_node()
216 {
217  if (_node == nullptr && get_can_driver() != nullptr) {
218  _node = new uavcan::Node<0>(*get_can_driver(), get_system_clock(), _node_allocator);
219  }
220 
221  return _node;
222 }
223 
224 uavcan::ICanDriver * UAVCAN_sniffer::get_can_driver()
225 {
226  if (_parent_can_mgr != nullptr) {
227  if (_parent_can_mgr->is_initialized() == false) {
228  return nullptr;
229  } else {
230  return _parent_can_mgr->get_driver();
231  }
232  }
233  return nullptr;
234 }
235 
236 uavcan::ISystemClock & UAVCAN_sniffer::get_system_clock()
237 {
238  return SystemClock::instance();
239 }
240 
241 void UAVCAN_sniffer::loop(void)
242 {
243  auto *node = get_node();
244  node->spin(uavcan::MonotonicDuration::fromMSec(1));
245 }
246 
247 void UAVCAN_sniffer::print_stats(void)
248 {
249  for (uint16_t i=0;i<100;i++) {
250  if (counters[i].msg_name == nullptr) {
251  break;
252  }
253  hal.console->printf("%s: %u\n", counters[i].msg_name, unsigned(counters[i].count));
254  counters[i].count = 0;
255  }
256  hal.console->printf("\n");
257 }
258 
259 static UAVCAN_sniffer sniffer;
260 
261 UAVCAN_sniffer::UAVCAN_sniffer() :
263 {}
264 
265 UAVCAN_sniffer::~UAVCAN_sniffer()
266 {
267 }
268 
269 void setup(void)
270 {
271  hal.scheduler->delay(2000);
272  hal.console->printf("Starting UAVCAN sniffer\n");
273  sniffer.init();
274 
275 }
276 
277 void loop(void)
278 {
279  sniffer.loop();
280  static uint32_t last_print_ms;
281  uint32_t now = AP_HAL::millis();
282  if (now - last_print_ms >= 1000) {
283  last_print_ms = now;
284  sniffer.print_stats();
285  }
286 
287  // auto-reboot for --upload
288  if (hal.console->available() > 50) {
289  hal.console->printf("rebooting\n");
290  while (hal.console->available()) {
291  hal.console->read();
292  }
293  hal.scheduler->reboot(false);
294  }
295  while (hal.console->available()) {
296  hal.console->read();
297  }
298 }
299 
300 AP_HAL_MAIN();
301 
302 #else
303 
304 #include <stdio.h>
305 
307 
308 static void loop() { }
309 static void setup()
310 {
311  printf("Board not currently supported\n");
312 }
313 
314 AP_HAL_MAIN();
315 #endif
static void setup()
int printf(const char *fmt,...)
Definition: stdio.c:113
#define AP_UAVCAN_SW_VERS_MAJOR
Definition: AP_UAVCAN.h:41
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define UAVCAN_NODE_POOL_SIZE
Definition: AP_UAVCAN.h:24
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uavcan::MonotonicTime getMonotonic()
const char * name
Definition: BusTest.cpp:11
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint32_t millis()
Definition: system.cpp:157
#define AP_UAVCAN_SW_VERS_MINOR
Definition: AP_UAVCAN.h:42
uint64_t micros64()
Definition: system.cpp:162
virtual int16_t read()=0
#define AP_UAVCAN_HW_VERS_MINOR
Definition: AP_UAVCAN.h:45
const HAL & get_HAL()
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL_MAIN()
virtual uint32_t available()=0
virtual void reboot(bool hold_in_bootloader)=0
void init()
Generic board initialization function.
Definition: system.cpp:136
static void loop()
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
#define ARRAY_SIZE_SIMPLE(_arr)
Definition: AP_Common.h:83
#define AP_UAVCAN_HW_VERS_MAJOR
Definition: AP_UAVCAN.h:44
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114