#include <canopen_master/canopen.h>
#include <canopen_master/master.h>
#include <boost/make_shared.hpp>
#include <iostream>
#include <socketcan_interface/dispatcher.h>
#include <boost/unordered_set.hpp>
#include <socketcan_interface/socketcan.h>
#include <socketcan_interface/threading.h>
#include <boost/thread.hpp>
Go to the source code of this file.
Functions | |
int | main (int argc, char *argv[]) |
void | print_frame (const Frame &f) |
void | print_node_state (const Node::State &s) |
void | print_state (const State &f) |
void | print_tpdo (const Frame &f) |
Variables | |
boost::shared_ptr < ThreadedInterface < SocketCANInterface > > | driver = boost::make_shared<ThreadedInterface<SocketCANInterface> > () |
void print_frame | ( | const Frame & | f | ) |
void print_node_state | ( | const Node::State & | s | ) |
void print_state | ( | const State & | f | ) |
void print_tpdo | ( | const Frame & | f | ) |
boost::shared_ptr<ThreadedInterface<SocketCANInterface> > driver = boost::make_shared<ThreadedInterface<SocketCANInterface> > () |