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


canopen_master
Author(s): Mathias Lüdtke
autogenerated on Wed Mar 2 2022 00:52:26