main.cpp
Go to the documentation of this file.
1 
20 #include <sys/socket.h>
21 #include <linux/sockios.h>
22 #include <linux/can.h>
23 #include <linux/if.h>
24 #include <time.h>
25 #include <stdio.h>
26 #include <string.h>
27 #include <fcntl.h>
28 #include <sys/types.h>
29 #include <errno.h>
30 #include <limits.h>
31 #include <sys/ioctl.h>
32 #include <boost/thread.hpp>
33 #include "CanListener.h"
34 #include "BaseController.h"
35 #include "RobotState.h"
36 
37 int main(int argc, char** argv)
38 {
39  ros::init(argc, argv, "Can");
41 
42  //Creating the socket for the CAN-Bus
43  int s;
44  struct sockaddr_can addr;
45  struct ifreq ifr;
46 
47  s = socket(PF_CAN, SOCK_RAW, CAN_RAW);
48 
49  strcpy(ifr.ifr_name, "can0" );
50  ioctl(s, SIOCGIFINDEX, &ifr);
51 
52  addr.can_family = AF_CAN;
53  addr.can_ifindex = ifr.ifr_ifindex;
54 
55  bind(s, (struct sockaddr *)&addr, sizeof(addr));
56  int bufsize = 256;
57  if(!setsockopt(s, SOL_SOCKET, SO_RCVBUF, &bufsize, sizeof(bufsize))){
58  ROS_INFO("Can: Socket set successfully.\n");
59  }else{
60  ROS_ERROR("Can: Socket set error.");
61  }
62 
63 
64  //Creating objects for the other files
65  RobotState state(&n, s);
66  CanListener canlist(&state);
67  BaseController controller(&state, &canlist);
68 
69  boost::thread list(boost::bind(&CanListener::run, &canlist));
70  boost::thread contr(boost::bind(&BaseController::run, &controller));
71 
72  ros::spin();
73 
74  list.join();
75  contr.join();
76 
77  close(s);
78  return 0;
79 }
int main(int argc, char **argv)
Definition: main.cpp:37
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
#define ROS_ERROR(...)


asr_mild_base_driving
Author(s): Aumann Florian, Borella Jocelyn, Dehmani Souheil, Marek Felix, Meißner Pascal, Reckling Reno
autogenerated on Mon Jun 10 2019 12:43:40