bcm_sync.cpp
Go to the documentation of this file.
3 
4 int main(int argc, char** argv){
5 
6  if(argc < 4){
7  std::cout << "Usage: " << argv[0] << " DEVICE PERIOD_MS HEADER [OVERFLOW] [+ID*] [-ID*] [--]" << std::endl;
8  return 1;
9  }
10 
11  std::string can_device = argv[1];
12  int sync_ms = atoi(argv[2]);
13  can::Header header = can::toheader(argv[3]);
14 
15  if(!header.isValid()){
16  std::cout << "header is invalid" << std::endl;
17  return 1;
18  }
19  int sync_overflow = 0;
20 
21  int start = 4;
22  if(argc > start && argv[start][0] != '-' && argv[start][0] != '+'){
23  sync_overflow = atoi(argv[4]);
24  if(sync_overflow == 1 || sync_overflow < 0 || sync_overflow > 240){
25  std::cout << "sync overflow is invalid" << std::endl;
26  return 1;
27  }
28  ++start;
29  }
30 
31  std::set<int> monitored, ignored;
32 
33  for(; argc > start; ++start){
34  if(strncmp("--", argv[start], 2) == 0) break;
35  int id = atoi(argv[start]);
36 
37  if(id > 0 && id < 128) monitored.insert(id);
38  else if (id < 0 && id > -128) ignored.insert(-id);
39  else{
40  std::cout << "ID is invalid: " << id << std::endl;
41  return 1;
42  }
43  }
44 
45  can::SocketCANDriverSharedPtr driver = boost::make_shared<can::SocketCANDriver>();
46  if(!driver->init(can_device, false)){
47  std::cout << "Could not initialize CAN" << std::endl;
48  return 1;
49  }
50 
51  canopen::SyncProperties sync_properties(header, sync_ms, sync_overflow);
52  canopen::BCMsync sync(can_device, driver, sync_properties);
53 
54  sync.setMonitored(monitored);
55  sync.setIgnored(ignored);
56 
57  canopen::LayerStatus status;
58  sync.init(status);
59  if(!status.bounded<canopen::LayerStatus::Warn>()){
60  std::cout << "Could not initialize sync" << std::endl;
61  return 1;
62  }
63 
64  driver->run();
65 
66  return 0;
67 }
void init(LayerStatus &status)
Definition: layer.h:85
Header toheader(const std::string &s)
bool isValid() const
void setMonitored(const T &other)
Definition: bcm_sync.h:156
void setIgnored(const T &other)
Definition: bcm_sync.h:160
int main(int argc, char **argv)
Definition: bcm_sync.cpp:4
boost::shared_ptr< SocketCANDriver > SocketCANDriverSharedPtr
bool bounded() const
Definition: layer.h:35


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