4 int main(
int argc,
char** argv){
7 std::cout <<
"Usage: " << argv[0] <<
" DEVICE PERIOD_MS HEADER [OVERFLOW] [+ID*] [-ID*] [--]" << std::endl;
11 std::string can_device = argv[1];
12 int sync_ms = atoi(argv[2]);
16 std::cout <<
"header is invalid" << std::endl;
19 int sync_overflow = 0;
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;
31 std::set<int> monitored, ignored;
33 for(; argc > start; ++start){
34 if(strncmp(
"--", argv[start], 2) == 0)
break;
35 int id = atoi(argv[start]);
37 if(
id > 0 &&
id < 128) monitored.insert(
id);
38 else if (id < 0 && id > -128) ignored.insert(-
id);
40 std::cout <<
"ID is invalid: " <<
id << std::endl;
46 if(!driver->init(can_device,
false)){
47 std::cout <<
"Could not initialize CAN" << std::endl;
60 std::cout <<
"Could not initialize sync" << std::endl;
void init(LayerStatus &status)
Header toheader(const std::string &s)
void setMonitored(const T &other)
void setIgnored(const T &other)
int main(int argc, char **argv)
boost::shared_ptr< SocketCANDriver > SocketCANDriverSharedPtr