APM:Libraries
AP_UAVCAN.h
Go to the documentation of this file.
1 /*
2  *
3  * Author: Eugene Shamaev
4  */
5 #ifndef AP_UAVCAN_H_
6 #define AP_UAVCAN_H_
7 
8 #include <uavcan/uavcan.hpp>
9 
10 #include <AP_HAL/CAN.h>
11 #include <AP_HAL/Semaphores.h>
12 #include <AP_GPS/AP_GPS.h>
13 #include <AP_Param/AP_Param.h>
14 
15 #include <AP_GPS/GPS_Backend.h>
17 #include <AP_Compass/AP_Compass.h>
19 
20 #include <uavcan/helpers/heap_based_pool_allocator.hpp>
21 #include <uavcan/equipment/indication/RGB565.hpp>
22 
23 #ifndef UAVCAN_NODE_POOL_SIZE
24 #define UAVCAN_NODE_POOL_SIZE 8192
25 #endif
26 
27 #ifndef UAVCAN_NODE_POOL_BLOCK_SIZE
28 #define UAVCAN_NODE_POOL_BLOCK_SIZE 256
29 #endif
30 
31 #ifndef UAVCAN_SRV_NUMBER
32 #define UAVCAN_SRV_NUMBER 18
33 #endif
34 
35 #define AP_UAVCAN_MAX_LISTENERS 4
36 #define AP_UAVCAN_MAX_GPS_NODES 4
37 #define AP_UAVCAN_MAX_MAG_NODES 4
38 #define AP_UAVCAN_MAX_BARO_NODES 4
39 #define AP_UAVCAN_MAX_BI_NUMBER 4
40 
41 #define AP_UAVCAN_SW_VERS_MAJOR 1
42 #define AP_UAVCAN_SW_VERS_MINOR 0
43 
44 #define AP_UAVCAN_HW_VERS_MAJOR 1
45 #define AP_UAVCAN_HW_VERS_MINOR 0
46 
47 #define AP_UAVCAN_MAX_LED_DEVICES 4
48 #define AP_UAVCAN_LED_DELAY_MILLISECONDS 50
49 
50 class AP_UAVCAN {
51 public:
52  AP_UAVCAN();
53  ~AP_UAVCAN();
54 
55  static const struct AP_Param::GroupInfo var_info[];
56 
57  // Return uavcan from @iface or nullptr if it's not ready or doesn't exist
58  static AP_UAVCAN *get_uavcan(uint8_t iface);
59 
60  // this function will register the listening class on a first free channel or on the specified channel
61  // if preferred_channel = 0 then free channel will be searched for
62  // if preferred_channel > 0 then listener will be added to specific channel
63  // return value is the number of assigned channel or 0 if fault
64  // channel numbering starts from 1
65  uint8_t register_gps_listener(AP_GPS_Backend* new_listener, uint8_t preferred_channel);
66 
67  uint8_t register_gps_listener_to_node(AP_GPS_Backend* new_listener, uint8_t node);
68 
69  uint8_t find_gps_without_listener(void);
70 
71  // Removes specified listener from all nodes
72  void remove_gps_listener(AP_GPS_Backend* rem_listener);
73 
74  // Returns pointer to GPS state connected with specified node.
75  // If node is not found and there are free space, locate a new one
76  AP_GPS::GPS_State *find_gps_node(uint8_t node);
77 
78  // Updates all listeners of specified node
79  void update_gps_state(uint8_t node);
80 
81  struct Baro_Info {
82  float pressure;
84  float temperature;
86  };
87 
88  uint8_t register_baro_listener(AP_Baro_Backend* new_listener, uint8_t preferred_channel);
89  uint8_t register_baro_listener_to_node(AP_Baro_Backend* new_listener, uint8_t node);
90  void remove_baro_listener(AP_Baro_Backend* rem_listener);
91  Baro_Info *find_baro_node(uint8_t node);
93  void update_baro_state(uint8_t node);
94 
95  struct Mag_Info {
97  };
98 
99  uint8_t register_mag_listener(AP_Compass_Backend* new_listener, uint8_t preferred_channel);
100  void remove_mag_listener(AP_Compass_Backend* rem_listener);
101  Mag_Info *find_mag_node(uint8_t node, uint8_t sensor_id);
102  uint8_t find_smallest_free_mag_node();
103  uint8_t register_mag_listener_to_node(AP_Compass_Backend* new_listener, uint8_t node);
104  void update_mag_state(uint8_t node, uint8_t sensor_id);
105 
107  float temperature;
108  float voltage;
109  float current;
112  uint8_t status_flags;
113  };
114 
115  uint8_t register_BM_bi_listener_to_id(AP_BattMonitor_Backend* new_listener, uint8_t id);
116  void remove_BM_bi_listener(AP_BattMonitor_Backend* rem_listener);
117  BatteryInfo_Info *find_bi_id(uint8_t id);
118  uint8_t find_smallest_free_bi_id();
119  void update_bi_state(uint8_t id);
120 
121  // synchronization for RC output
122  void SRV_sem_take();
123  void SRV_sem_give();
124 
125  // synchronization for LED output
126  bool led_out_sem_take();
127  void led_out_sem_give();
128  void led_out_send();
129 
130  // output from do_cyclic
131  void SRV_send_servos();
132  void SRV_send_esc();
133 
134 private:
135  // ------------------------- GPS
136  // 255 - means free node
138  // Counter of how many listeners are connected to this source
140  // GPS data of the sources
142 
143  // 255 - means no connection
145  // Listeners with callbacks to be updated
147 
148  // ------------------------- BARO
154 
155  // ------------------------- MAG
163 
164  // ------------------------- BatteryInfo
170 
171  struct {
172  uint16_t pulse;
173  uint16_t safety_pulse;
174  uint16_t failsafe_pulse;
178 
180  uint8_t _SRV_armed;
181  uint8_t _SRV_safety;
183 
184  typedef struct {
185  bool enabled;
186  uint8_t led_index;
187  uavcan::equipment::indication::RGB565 rgb565_color;
188  } _led_device;
189 
190  struct {
193  uint8_t devices_count;
194  uint64_t last_update;
195  } _led_conf;
196 
199 
200  class SystemClock: public uavcan::ISystemClock, uavcan::Noncopyable {
202  {
203  }
204 
205  uavcan::UtcDuration utc_adjustment;
206  virtual void adjustUtc(uavcan::UtcDuration adjustment)
207  {
208  utc_adjustment = adjustment;
209  }
210 
211  public:
212  virtual uavcan::MonotonicTime getMonotonic() const
213  {
214  uavcan::uint64_t usec = 0;
215  usec = AP_HAL::micros64();
216  return uavcan::MonotonicTime::fromUSec(usec);
217  }
218  virtual uavcan::UtcTime getUtc() const
219  {
220  uavcan::UtcTime utc;
221  uavcan::uint64_t usec = 0;
222  usec = AP_HAL::micros64();
223  utc.fromUSec(usec);
224  utc += utc_adjustment;
225  return utc;
226  }
227 
229  {
230  static SystemClock inst;
231  return inst;
232  }
233  };
234 
235  uavcan::Node<0> *_node = nullptr;
236 
237  uavcan::ISystemClock& get_system_clock();
238  uavcan::ICanDriver* get_can_driver();
239  uavcan::Node<0>* get_node();
240 
241  // This will be needed to implement if UAVCAN is used with multithreading
242  // Such cases will be firmware update, etc.
244  public:
246  {
247  }
248 
250  {
251  }
252  };
253 
254  uavcan::HeapBasedPoolAllocator<UAVCAN_NODE_POOL_BLOCK_SIZE, AP_UAVCAN::RaiiSynchronizer> _node_allocator;
255 
256  AP_Int8 _uavcan_node;
257  AP_Int32 _servo_bm;
258  AP_Int32 _esc_bm;
259  AP_Int16 _servo_rate_hz;
260 
261  uint8_t _uavcan_i;
262 
263  AP_HAL::CANManager* _parent_can_mgr;
264 
265 public:
266  void do_cyclic(void);
267  bool try_init(void);
268 
269  void SRV_set_safety_pwm(uint32_t chmask, uint16_t pulse_len);
270  void SRV_set_failsafe_pwm(uint32_t chmask, uint16_t pulse_len);
271  void SRV_force_safety_on(void);
272  void SRV_force_safety_off(void);
273  void SRV_arm_actuators(bool arm);
274  void SRV_write(uint16_t pulse_len, uint8_t ch);
275  void SRV_push_servos(void);
276  bool led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue);
277 
278  void set_parent_can_mgr(AP_HAL::CANManager* parent_can_mgr)
279  {
280  _parent_can_mgr = parent_can_mgr;
281  }
282 };
283 
284 #endif /* AP_UAVCAN_H_ */
AP_Int16 _servo_rate_hz
Definition: AP_UAVCAN.h:259
void SRV_push_servos(void)
Baro_Info * find_baro_node(uint8_t node)
bool servo_pending
Definition: AP_UAVCAN.h:176
void led_out_send()
struct AP_UAVCAN::@192 _led_conf
void update_baro_state(uint8_t node)
uint8_t _mag_node_max_sensorid_count[AP_UAVCAN_MAX_MAG_NODES]
Definition: AP_UAVCAN.h:159
void set_parent_can_mgr(AP_HAL::CANManager *parent_can_mgr)
Definition: AP_UAVCAN.h:278
BatteryInfo_Info _bi_id_state[AP_UAVCAN_MAX_BI_NUMBER]
Definition: AP_UAVCAN.h:167
uavcan::ICanDriver * get_can_driver()
AP_HAL::CANManager * _parent_can_mgr
Definition: AP_UAVCAN.h:263
uint8_t register_gps_listener_to_node(AP_GPS_Backend *new_listener, uint8_t node)
AP_Int32 _servo_bm
Definition: AP_UAVCAN.h:257
virtual uavcan::UtcTime getUtc() const
Definition: AP_UAVCAN.h:218
void remove_baro_listener(AP_Baro_Backend *rem_listener)
AP_Int8 _uavcan_node
Definition: AP_UAVCAN.h:256
void SRV_set_failsafe_pwm(uint32_t chmask, uint16_t pulse_len)
uint8_t register_mag_listener(AP_Compass_Backend *new_listener, uint8_t preferred_channel)
void update_gps_state(uint8_t node)
virtual void adjustUtc(uavcan::UtcDuration adjustment)
Definition: AP_UAVCAN.h:206
void remove_BM_bi_listener(AP_BattMonitor_Backend *rem_listener)
uint8_t _baro_node_taken[AP_UAVCAN_MAX_BARO_NODES]
Definition: AP_UAVCAN.h:150
#define UAVCAN_SRV_NUMBER
Definition: AP_UAVCAN.h:32
bool try_init(void)
AP_BattMonitor_Backend * _bi_BM_listeners[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:169
#define AP_UAVCAN_MAX_MAG_NODES
Definition: AP_UAVCAN.h:37
uint16_t pulse
Definition: AP_UAVCAN.h:172
static SystemClock & instance()
Definition: AP_UAVCAN.h:228
uavcan::Node< 0 > * _node
Definition: AP_UAVCAN.h:235
#define AP_UAVCAN_MAX_BARO_NODES
Definition: AP_UAVCAN.h:38
uint8_t _baro_listener_to_node[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:152
uavcan::UtcDuration utc_adjustment
Definition: AP_UAVCAN.h:205
void SRV_force_safety_off(void)
uint8_t find_smallest_free_baro_node()
uint16_t _bi_BM_listener_to_id[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:168
AP_GPS::GPS_State * find_gps_node(uint8_t node)
uint8_t _baro_nodes[AP_UAVCAN_MAX_BARO_NODES]
Definition: AP_UAVCAN.h:149
void update_mag_state(uint8_t node, uint8_t sensor_id)
bool led_out_sem_take()
uint8_t register_gps_listener(AP_GPS_Backend *new_listener, uint8_t preferred_channel)
bool broadcast_enabled
Definition: AP_UAVCAN.h:191
uavcan::equipment::indication::RGB565 rgb565_color
Definition: AP_UAVCAN.h:187
virtual uavcan::MonotonicTime getMonotonic() const
Definition: AP_UAVCAN.h:212
AP_Baro_Backend * _baro_listeners[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:153
uint8_t register_baro_listener_to_node(AP_Baro_Backend *new_listener, uint8_t node)
void remove_mag_listener(AP_Compass_Backend *rem_listener)
void SRV_send_esc()
A system for managing and storing variables that are of general interest to the system.
uint8_t _gps_node_taken[AP_UAVCAN_MAX_GPS_NODES]
Definition: AP_UAVCAN.h:139
uint16_t _bi_id[AP_UAVCAN_MAX_BI_NUMBER]
Definition: AP_UAVCAN.h:165
AP_GPS_Backend * _gps_listeners[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:146
Baro_Info _baro_node_state[AP_UAVCAN_MAX_BARO_NODES]
Definition: AP_UAVCAN.h:151
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_UAVCAN.h:55
AP_GPS::GPS_State _gps_node_state[AP_UAVCAN_MAX_GPS_NODES]
Definition: AP_UAVCAN.h:141
void SRV_arm_actuators(bool arm)
static AP_UAVCAN * get_uavcan(uint8_t iface)
uint16_t safety_pulse
Definition: AP_UAVCAN.h:173
bool led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue)
uint8_t _gps_nodes[AP_UAVCAN_MAX_GPS_NODES]
Definition: AP_UAVCAN.h:137
AP_Int32 _esc_bm
Definition: AP_UAVCAN.h:258
uint8_t _gps_listener_to_node[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:144
BatteryInfo_Info * find_bi_id(uint8_t id)
AP_HAL::Semaphore * _led_out_sem
Definition: AP_UAVCAN.h:198
uint64_t micros64()
Definition: system.cpp:162
uint8_t find_smallest_free_mag_node()
void remove_gps_listener(AP_GPS_Backend *rem_listener)
uint8_t _uavcan_i
Definition: AP_UAVCAN.h:261
uint8_t register_mag_listener_to_node(AP_Compass_Backend *new_listener, uint8_t node)
uint8_t register_baro_listener(AP_Baro_Backend *new_listener, uint8_t preferred_channel)
uavcan::HeapBasedPoolAllocator< UAVCAN_NODE_POOL_BLOCK_SIZE, AP_UAVCAN::RaiiSynchronizer > _node_allocator
Definition: AP_UAVCAN.h:254
void SRV_sem_give()
void SRV_sem_take()
uint8_t _SRV_safety
Definition: AP_UAVCAN.h:181
#define AP_UAVCAN_MAX_LISTENERS
Definition: AP_UAVCAN.h:35
#define AP_UAVCAN_MAX_LED_DEVICES
Definition: AP_UAVCAN.h:47
void SRV_send_servos()
void SRV_set_safety_pwm(uint32_t chmask, uint16_t pulse_len)
uint16_t _bi_id_taken[AP_UAVCAN_MAX_BI_NUMBER]
Definition: AP_UAVCAN.h:166
_led_device devices[AP_UAVCAN_MAX_LED_DEVICES]
Definition: AP_UAVCAN.h:192
#define AP_UAVCAN_MAX_GPS_NODES
Definition: AP_UAVCAN.h:36
uint8_t _mag_nodes[AP_UAVCAN_MAX_MAG_NODES]
Definition: AP_UAVCAN.h:156
Mag_Info * find_mag_node(uint8_t node, uint8_t sensor_id)
bool esc_pending
Definition: AP_UAVCAN.h:175
void do_cyclic(void)
uint32_t _SRV_last_send_us
Definition: AP_UAVCAN.h:182
uavcan::ISystemClock & get_system_clock()
uint8_t find_smallest_free_bi_id()
bool _initialized
Definition: AP_UAVCAN.h:179
#define AP_UAVCAN_MAX_BI_NUMBER
Definition: AP_UAVCAN.h:39
uavcan::Node< 0 > * get_node()
void led_out_sem_give()
uint8_t find_gps_without_listener(void)
uint16_t failsafe_pulse
Definition: AP_UAVCAN.h:174
uint8_t devices_count
Definition: AP_UAVCAN.h:193
struct AP_UAVCAN::@191 _SRV_conf[UAVCAN_SRV_NUMBER]
uint8_t _SRV_armed
Definition: AP_UAVCAN.h:180
uint64_t last_update
Definition: AP_UAVCAN.h:194
Mag_Info _mag_node_state[AP_UAVCAN_MAX_MAG_NODES]
Definition: AP_UAVCAN.h:158
uint8_t _mag_node_taken[AP_UAVCAN_MAX_MAG_NODES]
Definition: AP_UAVCAN.h:157
Vector3f mag_vector
Definition: AP_UAVCAN.h:96
uint8_t register_BM_bi_listener_to_id(AP_BattMonitor_Backend *new_listener, uint8_t id)
AP_HAL::Semaphore * SRV_sem
Definition: AP_UAVCAN.h:197
void SRV_write(uint16_t pulse_len, uint8_t ch)
void update_bi_state(uint8_t id)
void SRV_force_safety_on(void)
float temperature_variance
Definition: AP_UAVCAN.h:85
uint8_t _mag_listener_sensor_ids[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:162
AP_Compass_Backend * _mag_listeners[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:161
uint8_t _mag_listener_to_node[AP_UAVCAN_MAX_LISTENERS]
Definition: AP_UAVCAN.h:160