7 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && HAL_WITH_UAVCAN 9 #include <uavcan/uavcan.hpp> 15 #include <uavcan/helpers/heap_based_pool_allocator.hpp> 16 #include <uavcan/equipment/indication/RGB565.hpp> 18 #include <uavcan/equipment/gnss/Fix.hpp> 19 #include <uavcan/equipment/gnss/Auxiliary.hpp> 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> 26 #include <uavcan/equipment/actuator/ArrayCommand.hpp> 27 #include <uavcan/equipment/actuator/Command.hpp> 28 #include <uavcan/equipment/actuator/Status.hpp> 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> 35 #include <uavcan/equipment/power/BatteryInfo.hpp> 42 #define UAVCAN_NODE_POOL_SIZE 8192 43 #define UAVCAN_NODE_POOL_BLOCK_SIZE 256 45 #define debug_uavcan(level, fmt, args...) do { hal.console->printf(fmt, ##args); } while (0) 47 class UAVCAN_sniffer {
54 void print_stats(
void);
59 class SystemClock:
public uavcan::ISystemClock, uavcan::Noncopyable {
64 uavcan::UtcDuration utc_adjustment;
65 virtual void adjustUtc(uavcan::UtcDuration adjustment)
67 utc_adjustment = adjustment;
73 uavcan::uint64_t usec = 0;
75 return uavcan::MonotonicTime::fromUSec(usec);
77 virtual uavcan::UtcTime getUtc()
const 80 uavcan::uint64_t usec = 0;
83 utc += utc_adjustment;
87 static SystemClock& instance()
89 static SystemClock inst;
94 uavcan::Node<0> *_node;
96 uavcan::ISystemClock& get_system_clock();
97 uavcan::ICanDriver* get_can_driver();
98 uavcan::Node<0>* get_node();
102 class RaiiSynchronizer {
113 uavcan::HeapBasedPoolAllocator<UAVCAN_NODE_POOL_BLOCK_SIZE, UAVCAN_sniffer::RaiiSynchronizer> _node_allocator;
115 AP_HAL::CANManager* _parent_can_mgr;
117 void set_parent_can_mgr(AP_HAL::CANManager* parent_can_mgr)
119 _parent_can_mgr = parent_can_mgr;
124 const char *msg_name;
128 static void count_msg(
const char *
name)
131 if (counters[i].msg_name == name) {
135 if (counters[i].msg_name ==
nullptr) {
136 counters[i].msg_name =
name;
143 #define MSG_CB(mtype, cbname) \ 144 static void cb_ ## cbname(const uavcan::ReceivedDataStructure<mtype>& msg) { count_msg(msg.getDataTypeFullName()); } 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)
158 const_cast <
AP_HAL::HAL&> (
hal).can_mgr[inum] =
new ChibiOS::CANManager;
159 hal.
can_mgr[0]->begin(1000000, inum);
161 set_parent_can_mgr(hal.
can_mgr[inum]);
163 if (!_parent_can_mgr->is_initialized()) {
168 auto *node = get_node();
170 uavcan::NodeID self_node_id(9);
171 node->setNodeID(self_node_id);
174 snprintf(ndname,
sizeof(ndname),
"org.ardupilot:%u", inum);
176 uavcan::NodeStatusProvider::NodeName
name(ndname);
179 uavcan::protocol::SoftwareVersion sw_version;
182 node->setSoftwareVersion(sw_version);
184 uavcan::protocol::HardwareVersion hw_version;
188 node->setHardwareVersion(hw_version);
190 const int node_start_res = node->start();
191 if (node_start_res < 0) {
192 debug_uavcan(1,
"UAVCAN: node start problem\n\r");
195 #define START_CB(mtype, cbname) (new uavcan::Subscriber<mtype>(*node))->start(cb_ ## cbname) 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);
210 node->setModeOperational();
212 debug_uavcan(1,
"UAVCAN: init done\n\r");
215 uavcan::Node<0> *UAVCAN_sniffer::get_node()
217 if (_node ==
nullptr && get_can_driver() !=
nullptr) {
218 _node =
new uavcan::Node<0>(*get_can_driver(), get_system_clock(), _node_allocator);
224 uavcan::ICanDriver * UAVCAN_sniffer::get_can_driver()
226 if (_parent_can_mgr !=
nullptr) {
227 if (_parent_can_mgr->is_initialized() ==
false) {
230 return _parent_can_mgr->get_driver();
236 uavcan::ISystemClock & UAVCAN_sniffer::get_system_clock()
238 return SystemClock::instance();
243 auto *node = get_node();
244 node->spin(uavcan::MonotonicDuration::fromMSec(1));
247 void UAVCAN_sniffer::print_stats(
void)
249 for (uint16_t i=0;i<100;i++) {
250 if (counters[i].msg_name ==
nullptr) {
254 counters[i].count = 0;
259 static UAVCAN_sniffer sniffer;
261 UAVCAN_sniffer::UAVCAN_sniffer() :
265 UAVCAN_sniffer::~UAVCAN_sniffer()
280 static uint32_t last_print_ms;
282 if (now - last_print_ms >= 1000) {
284 sniffer.print_stats();
311 printf(
"Board not currently supported\n");
int printf(const char *fmt,...)
#define AP_UAVCAN_SW_VERS_MAJOR
AP_HAL::UARTDriver * console
#define UAVCAN_NODE_POOL_SIZE
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uavcan::MonotonicTime getMonotonic()
AP_HAL::CANManager ** can_mgr
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
#define AP_UAVCAN_SW_VERS_MINOR
#define AP_UAVCAN_HW_VERS_MINOR
Common definitions and utility routines for the ArduPilot libraries.
virtual uint32_t available()=0
virtual void reboot(bool hold_in_bootloader)=0
void init()
Generic board initialization function.
int snprintf(char *str, size_t size, const char *fmt,...)
#define ARRAY_SIZE_SIMPLE(_arr)
#define AP_UAVCAN_HW_VERS_MAJOR
AP_HAL::Scheduler * scheduler