candump.cpp
Go to the documentation of this file.
1 #include <iostream>
2 #include <boost/unordered_set.hpp>
3 #include <boost/exception/diagnostic_information.hpp>
4 #include <boost/make_shared.hpp>
7 
8 using namespace can;
9 
10 #include <iostream>
11 
12 void print_error(const State & s);
13 
14 void print_frame(const Frame &f){
15 
16  if(f.is_error){
17  std::cout << "E " << std::hex << f.id << std::dec;
18  }else if(f.is_extended){
19  std::cout << "e " << std::hex << f.id << std::dec;
20  }else{
21  std::cout << "s " << std::hex << f.id << std::dec;
22  }
23 
24  std::cout << "\t";
25 
26  if(f.is_rtr){
27  std::cout << "r";
28  }else{
29  std::cout << (int) f.dlc << std::hex;
30 
31  for(int i=0; i < f.dlc; ++i){
32  std::cout << std::hex << " " << (int) f.data[i];
33  }
34  }
35 
36  std::cout << std::dec << std::endl;
37 }
38 
39 
40 boost::shared_ptr<class_loader::ClassLoader> g_loader;
42 
43 void print_error(const State & s){
44  std::string err;
45  g_driver->translateError(s.internal_error,err);
46  std::cout << "ERROR: state=" << s.driver_state << " internal_error=" << s.internal_error << "('" << err << "') asio: " << s.error_code << std::endl;
47 }
48 
49 
50 int main(int argc, char *argv[]){
51 
52  if(argc != 2 && argc != 4){
53  std::cout << "usage: "<< argv[0] << " DEVICE [PLUGIN_PATH PLUGIN_NAME]" << std::endl;
54  return 1;
55  }
56 
57  if(argc == 4 ){
58  try
59  {
60  g_loader = boost::make_shared<class_loader::ClassLoader>(argv[2]);
61  g_driver = g_loader->createInstance<DriverInterface>(argv[3]);
62  }
63 
64  catch(std::exception& ex)
65  {
66  std::cerr << boost::diagnostic_information(ex) << std::endl;;
67  return 1;
68  }
69  }else{
70  g_driver = boost::make_shared<SocketCANInterface>();
71  }
72 
73 
74 
75  FrameListenerConstSharedPtr frame_printer = g_driver->createMsgListener(print_frame);
76  StateListenerConstSharedPtr error_printer = g_driver->createStateListener(print_error);
77 
78  if(!g_driver->init(argv[1], false)){
79  print_error(g_driver->getState());
80  return 1;
81  }
82 
83  g_driver->run();
84 
85  g_driver->shutdown();
86  g_driver.reset();
87  g_loader.reset();
88 
89  return 0;
90 
91 }
void print_error(const State &s)
Definition: candump.cpp:43
DriverInterfaceSharedPtr g_driver
Definition: candump.cpp:41
unsigned int is_error
marks an error frame (only used internally)
Definition: interface.h:20
Definition: asio_base.h:11
void print_frame(const Frame &f)
Definition: candump.cpp:14
boost::array< value_type, 8 > data
array for 8 data bytes with bounds checking
Definition: interface.h:58
unsigned int is_extended
frame uses 29 bit CAN identifier
Definition: interface.h:22
boost::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
Definition: interface.h:201
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
Definition: interface.h:160
enum can::State::DriverState driver_state
int main(int argc, char *argv[])
Definition: candump.cpp:50
unsigned int internal_error
driver specific error
Definition: interface.h:86
StateInterface::StateListenerConstSharedPtr StateListenerConstSharedPtr
Definition: interface.h:124
unsigned char dlc
len of data
Definition: interface.h:59
unsigned int id
CAN ID (11 or 29 bits valid, depending on is_extended member.
Definition: interface.h:19
unsigned int is_rtr
frame is a remote transfer request
Definition: interface.h:21
boost::shared_ptr< class_loader::ClassLoader > g_loader
Definition: candump.cpp:40
boost::system::error_code error_code
device access error
Definition: interface.h:85


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:41