Go to the documentation of this file.00001
00020 #include <sys/socket.h>
00021 #include <linux/sockios.h>
00022 #include <linux/can.h>
00023 #include <linux/if.h>
00024 #include <time.h>
00025 #include <stdio.h>
00026 #include <string.h>
00027 #include <fcntl.h>
00028 #include <sys/types.h>
00029 #include <errno.h>
00030 #include <limits.h>
00031 #include <sys/ioctl.h>
00032 #include <boost/thread.hpp>
00033 #include "CanListener.h"
00034 #include "BaseController.h"
00035 #include "RobotState.h"
00036
00037 int main(int argc, char** argv)
00038 {
00039 ros::init(argc, argv, "Can");
00040 ros::NodeHandle n;
00041
00042
00043 int s;
00044 struct sockaddr_can addr;
00045 struct ifreq ifr;
00046
00047 s = socket(PF_CAN, SOCK_RAW, CAN_RAW);
00048
00049 strcpy(ifr.ifr_name, "can0" );
00050 ioctl(s, SIOCGIFINDEX, &ifr);
00051
00052 addr.can_family = AF_CAN;
00053 addr.can_ifindex = ifr.ifr_ifindex;
00054
00055 bind(s, (struct sockaddr *)&addr, sizeof(addr));
00056 int bufsize = 256;
00057 if(!setsockopt(s, SOL_SOCKET, SO_RCVBUF, &bufsize, sizeof(bufsize))){
00058 ROS_INFO("Can: Socket set successfully.\n");
00059 }else{
00060 ROS_ERROR("Can: Socket set error.");
00061 }
00062
00063
00064
00065 RobotState state(&n, s);
00066 CanListener canlist(&state);
00067 BaseController controller(&state, &canlist);
00068
00069 boost::thread list(boost::bind(&CanListener::run, &canlist));
00070 boost::thread contr(boost::bind(&BaseController::run, &controller));
00071
00072 ros::spin();
00073
00074 list.join();
00075 contr.join();
00076
00077 close(s);
00078 return 0;
00079 }
asr_mild_base_driving
Author(s): Aumann Florian, Borella Jocelyn, Dehmani Souheil, Marek Felix, Meißner Pascal, Reckling Reno
autogenerated on Thu Jun 6 2019 22:02:58