Go to the documentation of this file.00001 #include <canopen_master/bcm_sync.h>
00002 #include <socketcan_interface/string.h>
00003
00004 int main(int argc, char** argv){
00005
00006 if(argc < 4){
00007 std::cout << "Usage: " << argv[0] << " DEVICE PERIOD_MS HEADER [OVERFLOW] [+ID*] [-ID*] [--]" << std::endl;
00008 return 1;
00009 }
00010
00011 std::string can_device = argv[1];
00012 int sync_ms = atoi(argv[2]);
00013 can::Header header = can::toheader(argv[3]);
00014
00015 if(!header.isValid()){
00016 std::cout << "header is invalid" << std::endl;
00017 return 1;
00018 }
00019 int sync_overflow = 0;
00020
00021 int start = 4;
00022 if(argc > start && argv[start][0] != '-' && argv[start][0] != '+'){
00023 sync_overflow = atoi(argv[4]);
00024 if(sync_overflow == 1 || sync_overflow < 0 || sync_overflow > 240){
00025 std::cout << "sync overflow is invalid" << std::endl;
00026 return 1;
00027 }
00028 ++start;
00029 }
00030
00031 std::set<int> monitored, ignored;
00032
00033 for(; argc > start; ++start){
00034 if(strncmp("--", argv[start], 2) == 0) break;
00035 int id = atoi(argv[start]);
00036
00037 if(id > 0 && id < 128) monitored.insert(id);
00038 else if (id < 0 && id > -128) ignored.insert(-id);
00039 else{
00040 std::cout << "ID is invalid: " << id << std::endl;
00041 return 1;
00042 }
00043 }
00044
00045 boost::shared_ptr<can::SocketCANDriver> driver = boost::make_shared<can::SocketCANDriver>();
00046 if(!driver->init(can_device, false)){
00047 std::cout << "Could not initialize CAN" << std::endl;
00048 return 1;
00049 }
00050
00051 canopen::SyncProperties sync_properties(header, sync_ms, sync_overflow);
00052 canopen::BCMsync sync(can_device, driver, sync_properties);
00053
00054 sync.setMonitored(monitored);
00055 sync.setIgnored(ignored);
00056
00057 canopen::LayerStatus status;
00058 sync.init(status);
00059 if(!status.bounded<canopen::LayerStatus::Warn>()){
00060 std::cout << "Could not initialize sync" << std::endl;
00061 return 1;
00062 }
00063
00064 driver->run();
00065
00066 return 0;
00067 }