8 #include <uavcan/uavcan.hpp> 20 #include <uavcan/helpers/heap_based_pool_allocator.hpp> 21 #include <uavcan/equipment/indication/RGB565.hpp> 23 #ifndef UAVCAN_NODE_POOL_SIZE 24 #define UAVCAN_NODE_POOL_SIZE 8192 27 #ifndef UAVCAN_NODE_POOL_BLOCK_SIZE 28 #define UAVCAN_NODE_POOL_BLOCK_SIZE 256 31 #ifndef UAVCAN_SRV_NUMBER 32 #define UAVCAN_SRV_NUMBER 18 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 41 #define AP_UAVCAN_SW_VERS_MAJOR 1 42 #define AP_UAVCAN_SW_VERS_MINOR 0 44 #define AP_UAVCAN_HW_VERS_MAJOR 1 45 #define AP_UAVCAN_HW_VERS_MINOR 0 47 #define AP_UAVCAN_MAX_LED_DEVICES 4 48 #define AP_UAVCAN_LED_DELAY_MILLISECONDS 50 200 class SystemClock:
public uavcan::ISystemClock, uavcan::Noncopyable {
208 utc_adjustment = adjustment;
214 uavcan::uint64_t usec = 0;
216 return uavcan::MonotonicTime::fromUSec(usec);
221 uavcan::uint64_t usec = 0;
224 utc += utc_adjustment;
254 uavcan::HeapBasedPoolAllocator<UAVCAN_NODE_POOL_BLOCK_SIZE, AP_UAVCAN::RaiiSynchronizer>
_node_allocator;
274 void SRV_write(uint16_t pulse_len, uint8_t ch);
276 bool led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue);
280 _parent_can_mgr = parent_can_mgr;
void SRV_push_servos(void)
Baro_Info * find_baro_node(uint8_t node)
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]
void set_parent_can_mgr(AP_HAL::CANManager *parent_can_mgr)
BatteryInfo_Info _bi_id_state[AP_UAVCAN_MAX_BI_NUMBER]
uavcan::ICanDriver * get_can_driver()
AP_HAL::CANManager * _parent_can_mgr
uint8_t register_gps_listener_to_node(AP_GPS_Backend *new_listener, uint8_t node)
virtual uavcan::UtcTime getUtc() const
void remove_baro_listener(AP_Baro_Backend *rem_listener)
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)
void remove_BM_bi_listener(AP_BattMonitor_Backend *rem_listener)
uint8_t _baro_node_taken[AP_UAVCAN_MAX_BARO_NODES]
#define UAVCAN_SRV_NUMBER
AP_BattMonitor_Backend * _bi_BM_listeners[AP_UAVCAN_MAX_LISTENERS]
#define AP_UAVCAN_MAX_MAG_NODES
static SystemClock & instance()
uavcan::Node< 0 > * _node
#define AP_UAVCAN_MAX_BARO_NODES
uint8_t _baro_listener_to_node[AP_UAVCAN_MAX_LISTENERS]
uavcan::UtcDuration utc_adjustment
void SRV_force_safety_off(void)
uint8_t find_smallest_free_baro_node()
uint16_t _bi_BM_listener_to_id[AP_UAVCAN_MAX_LISTENERS]
AP_GPS::GPS_State * find_gps_node(uint8_t node)
uint8_t _baro_nodes[AP_UAVCAN_MAX_BARO_NODES]
void update_mag_state(uint8_t node, uint8_t sensor_id)
uint8_t register_gps_listener(AP_GPS_Backend *new_listener, uint8_t preferred_channel)
uavcan::equipment::indication::RGB565 rgb565_color
virtual uavcan::MonotonicTime getMonotonic() const
AP_Baro_Backend * _baro_listeners[AP_UAVCAN_MAX_LISTENERS]
uint8_t register_baro_listener_to_node(AP_Baro_Backend *new_listener, uint8_t node)
void remove_mag_listener(AP_Compass_Backend *rem_listener)
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]
uint16_t _bi_id[AP_UAVCAN_MAX_BI_NUMBER]
AP_GPS_Backend * _gps_listeners[AP_UAVCAN_MAX_LISTENERS]
Baro_Info _baro_node_state[AP_UAVCAN_MAX_BARO_NODES]
static const struct AP_Param::GroupInfo var_info[]
AP_GPS::GPS_State _gps_node_state[AP_UAVCAN_MAX_GPS_NODES]
void SRV_arm_actuators(bool arm)
static AP_UAVCAN * get_uavcan(uint8_t iface)
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]
uint8_t _gps_listener_to_node[AP_UAVCAN_MAX_LISTENERS]
BatteryInfo_Info * find_bi_id(uint8_t id)
AP_HAL::Semaphore * _led_out_sem
uint8_t find_smallest_free_mag_node()
void remove_gps_listener(AP_GPS_Backend *rem_listener)
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
#define AP_UAVCAN_MAX_LISTENERS
#define AP_UAVCAN_MAX_LED_DEVICES
void SRV_set_safety_pwm(uint32_t chmask, uint16_t pulse_len)
uint16_t _bi_id_taken[AP_UAVCAN_MAX_BI_NUMBER]
_led_device devices[AP_UAVCAN_MAX_LED_DEVICES]
#define AP_UAVCAN_MAX_GPS_NODES
uint8_t _mag_nodes[AP_UAVCAN_MAX_MAG_NODES]
Mag_Info * find_mag_node(uint8_t node, uint8_t sensor_id)
uint32_t _SRV_last_send_us
uavcan::ISystemClock & get_system_clock()
uint8_t find_smallest_free_bi_id()
float full_charge_capacity_wh
#define AP_UAVCAN_MAX_BI_NUMBER
uavcan::Node< 0 > * get_node()
uint8_t find_gps_without_listener(void)
struct AP_UAVCAN::@191 _SRV_conf[UAVCAN_SRV_NUMBER]
Mag_Info _mag_node_state[AP_UAVCAN_MAX_MAG_NODES]
uint8_t _mag_node_taken[AP_UAVCAN_MAX_MAG_NODES]
uint8_t register_BM_bi_listener_to_id(AP_BattMonitor_Backend *new_listener, uint8_t id)
AP_HAL::Semaphore * SRV_sem
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
uint8_t _mag_listener_sensor_ids[AP_UAVCAN_MAX_LISTENERS]
AP_Compass_Backend * _mag_listeners[AP_UAVCAN_MAX_LISTENERS]
float remaining_capacity_wh
uint8_t _mag_listener_to_node[AP_UAVCAN_MAX_LISTENERS]