6 # define UAVCAN_DEBUG 1 11 #include <condition_variable> 15 #include <uavcan/protocol/debug/KeyValue.hpp> 29 template <
typename... Args>
38 allocator_(arg_allocator, block_allocation_quota)
50 template <
typename... Args>
62 assert(item !=
nullptr);
72 while (p->getNextListNode() !=
nullptr)
74 p = p->getNextListNode();
76 assert(p->getNextListNode() ==
nullptr);
77 p->setNextListNode(item);
78 assert(p->getNextListNode()->getNextListNode() ==
nullptr);
90 const T*
peek()
const {
return isEmpty() ? nullptr : &list_.
get()->payload; }
100 assert(item !=
nullptr);
160 std::lock_guard<std::mutex> lock(mutex_);
161 prioritized_tx_queue_.
push(frame, tx_deadline, uavcan::CanTxQueue::Volatile, flags);
168 std::lock_guard<std::mutex> lock(mutex_);
175 const auto item = *rx_queue_.
peek();
178 out_frame = item.frame;
179 out_ts_monotonic = item.frame.ts_mono;
180 out_ts_utc = item.frame.ts_utc;
181 out_flags = item.flags;
192 std::mutex& arg_mutex,
unsigned quota_per_queue) :
194 prioritized_tx_queue_(allocator, clock, quota_per_queue),
195 rx_queue_(allocator, quota_per_queue)
205 std::lock_guard<std::mutex> lock(mutex_);
219 std::lock_guard<std::mutex> lock(mutex_);
223 while (
auto e = prioritized_tx_queue_.
peek())
225 UAVCAN_TRACE(
"VirtualCanIface",
"TX injection [iface=0x%02x]: %s",
226 unsigned(iface_mask), e->toString().c_str());
228 const int res = main_node.
injectTxFrame(e->frame, e->deadline, iface_mask,
229 uavcan::CanTxQueue::Qos(e->qos), e->flags);
230 prioritized_tx_queue_.
remove(e);
244 std::lock_guard<std::mutex> lock(mutex_);
262 virtual void injectTxFramesInto(
uavcan::INode& main_node) = 0;
272 template <
unsigned SharedMemoryPoolSize>
281 std::condition_variable
cv_;
289 std::unique_lock<std::mutex> lk(m_);
290 (void)cv_.wait_for(lk, std::chrono::microseconds(duration.
toUSec()));
305 return (iface_index < num_ifaces_) ? ifaces_[iface_index].operator
VirtualCanIface*() :
nullptr;
317 bool need_block = (inout_masks.
write == 0);
318 for (
unsigned i = 0; need_block && (i < num_ifaces_); i++)
320 const bool need_read = inout_masks.
read & (1U << i);
321 if (need_read && ifaces_[i]->hasDataInRxQueue())
333 for (
unsigned i = 0; i < num_ifaces_; i++)
336 inout_masks.
write |= iface_mask;
337 if (ifaces_[i]->hasDataInRxQueue())
339 inout_masks.
read |= iface_mask;
351 UAVCAN_TRACE(
"VirtualCanDriver",
"RX [flags=%u]: %s",
unsigned(flags), frame.toString().c_str());
364 for (
unsigned i = 0; i < num_ifaces_; i++)
376 const unsigned quota_per_iface = allocator_.
getBlockCapacity() / num_ifaces_;
377 const unsigned quota_per_queue = quota_per_iface;
379 UAVCAN_TRACE(
"VirtualCanDriver",
"Total blocks: %u, quota per queue: %u",
382 for (
unsigned i = 0; i < num_ifaces_; i++)
385 std::mutex&,
unsigned>(
allocator_, clock_, mutex_, quota_per_queue);
391 const std::string& name)
393 std::cout <<
"Initializing main node" << std::endl;
396 uavcan::protocol::SoftwareVersion(), uavcan::protocol::HardwareVersion(), nid);
397 node->getLogger().setLevel(uavcan::protocol::debug::LogLevel::DEBUG);
398 node->setModeOperational();
402 template <
unsigned QueuePoolSize>
405 std::cout <<
"Initializing sub node" << std::endl;
409 std::shared_ptr<Driver> driver(
new Driver(num_ifaces));
420 std::cout <<
"Running main node" << std::endl;
424 node->logInfo(
"timer",
"Your time is running out.");
426 node->setVendorSpecificStatusCode(static_cast<std::uint16_t>(
std::rand()));
434 if (node->getDispatcher().getRxFrameListener() ==
nullptr)
436 throw std::logic_error(
"RX frame listener is not configured");
445 node->logError(
"spin",
"Error %*", res);
454 std::cout <<
"Running sub node" << std::endl;
459 auto log_sub = node->makeSubscriber<uavcan::protocol::debug::LogMessage>(
462 std::cout << msg << std::endl;
472 virtual void handleNodeStatusChange(
const NodeStatusChangeEvent& event)
override 474 std::cout <<
"Remote node NID " <<
int(event.node_id.get()) <<
" changed status: " 475 << event.old_status.toString() <<
" --> " <<
event.status.toString() << std::endl;
478 NodeStatusMonitor nsm(*node);
484 auto kv_sub = node->makeSubscriber<uavcan::protocol::debug::KeyValue>(
487 std::cout << msg << std::endl;
493 unsigned kv_value = 0;
494 auto kv_pub = node->makePublisher<uavcan::protocol::debug::KeyValue>();
497 uavcan::protocol::debug::KeyValue kv;
498 kv.key =
"five_seconds";
499 kv.value = kv_value++;
500 const int res = kv_pub->broadcast(kv);
503 std::cerr <<
"Sub KV pub err " << res << std::endl;
512 std::cerr <<
"SubNode spin error: " << res << std::endl;
517 int main(
int argc,
const char** argv)
523 constexpr
unsigned VirtualIfacePoolSize = 32768;
527 std::cerr <<
"Usage:\n\t" << argv[0] <<
" <node-id> <can-iface-name-1> [can-iface-name-N...]" << std::endl;
531 const int self_node_id = std::stoi(argv[1]);
532 std::vector<std::string> iface_names(argv + 2, argv + argc);
534 auto node =
initMainNode(iface_names, self_node_id,
"org.uavcan.linux_test_node");
535 auto sub_node = initSubNode<VirtualIfacePoolSize>(iface_names.size(), *
node);
537 std::thread sub_thread([&sub_node](){
runSubNode(sub_node); });
541 if (sub_thread.joinable())
543 std::cout <<
"Waiting for the sub thread to join" << std::endl;
549 catch (
const std::exception& ex)
551 std::cerr <<
"Exception: " << ex.what() << std::endl;
void injectTxFramesInto(uavcan::INode &main_node) override
virtual void deallocate(const void *ptr)
void addRxFrame(const uavcan::CanRxFrame &frame, uavcan::CanIOFlags flags)
Dispatcher & getDispatcher()
void push(const CanFrame &frame, MonotonicTime tx_deadline, CanIOFlags flags)
uavcan::MonotonicTime getMonotonic() const override
VirtualCanDriver(unsigned arg_num_ifaces)
int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
void waitFor(uavcan::MonotonicDuration duration)
static uavcan_linux::NodePtr initMainNode(const std::vector< std::string > &ifaces, uavcan::NodeID nid, const std::string &name)
static void runMainNode(const uavcan_linux::NodePtr &node)
Queue< RxItem > rx_queue_
std::shared_ptr< SubNode > SubNodePtr
Queue(uavcan::IPoolAllocator &arg_allocator, std::size_t block_allocation_quota)
void installRxFrameListener(IRxFrameListener *listener)
int16_t configureFilters(const uavcan::CanFilterConfig *, std::uint16_t) override
#define UAVCAN_TRACE(...)
uavcan_linux::SystemClock clock_
virtual void injectTxFramesInto(uavcan::INode &main_node)=0
static uavcan_linux::SubNodePtr initSubNode(unsigned num_ifaces, uavcan::INode &main_node)
void remove(CanTxQueueEntry *entry)
int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
Implicitly convertible to/from uavcan.Timestamp.
uint8_t getNumIfaces() const override
std::shared_ptr< Node > NodePtr
void handleRxFrame(const uavcan::CanRxFrame &frame, uavcan::CanIOFlags flags) override
uavcan::PoolAllocator< SharedMemoryPoolSize, uavcan::MemPoolBlockSize > allocator_
Shared across all ifaces.
virtual ~ITxQueueInjector()
static SubNodePtr makeSubNode(const std::vector< std::string > &iface_names, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
void flushTxQueueTo(uavcan::INode &main_node, std::uint8_t iface_index)
VirtualCanIface(uavcan::IPoolAllocator &allocator, uavcan::ISystemClock &clock, std::mutex &arg_mutex, unsigned quota_per_queue)
static void runSubNode(const uavcan_linux::SubNodePtr &node)
uint16_t getNumFilters() const override
const uavcan::CanRxFrame frame
virtual void * allocate(std::size_t size)
uavcan::CanTxQueue prioritized_tx_queue_
std::mutex mutex_
Shared across all ifaces.
const unsigned num_ifaces_
uavcan::ICanIface * getIface(uint8_t iface_index) override
bool hasDataInRxQueue() const
static NodePtr makeNode(const std::vector< std::string > &iface_names, ClockAdjustmentMode clock_adjustment_mode=SystemClock::detectPreferredClockAdjustmentMode())
int injectTxFrame(const CanFrame &frame, MonotonicTime tx_deadline, uint8_t iface_mask, CanIOFlags flags=0)
uavcan::LinkedListRoot< Item > list_
int main(int argc, const char **argv)
std::condition_variable cv_
virtual uint16_t getBlockCapacity() const
static MonotonicDuration fromMSec(int64_t ms)
void remove(const T *node)
int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override
uint64_t getErrorCount() const override
const uavcan::CanIOFlags flags
bool tryEmplace(Args... args)
uavcan::LimitedPoolAllocator allocator_
Event event_
Used to unblock the select() call when IO happens.
RxItem(const uavcan::CanRxFrame &arg_frame, uavcan::CanIOFlags arg_flags)