innok_heros_can_driver.cpp
Go to the documentation of this file.
1 /* Copyright 2017 Innok Robotics GmbH */
2 
3 #include <stdio.h>
4 #include <string.h>
5 #include <fcntl.h>
6 #include <sys/ioctl.h>
7 #include <net/if.h>
8 #include <linux/can.h>
9 #include <linux/can/raw.h>
10 #include <ros/ros.h>
11 #include <geometry_msgs/Twist.h>
12 #include <geometry_msgs/Point.h>
13 #include <geometry_msgs/Quaternion.h>
14 #include <nav_msgs/Odometry.h>
15 #include <sensor_msgs/Joy.h>
16 #include <std_msgs/Float32.h>
18 #include <boost/thread/thread.hpp>
19 #include <boost/thread/mutex.hpp>
20 
21 
22 // Prototypes
23 void publishJoyMsg();
24 void publishOdomMsg();
25 void publishVoltageMsg();
26 
27 // Variables
29 
30 double battery_voltage = 0;
31 double odom_orientation = 0;
32 double odom_pos_x = 0;
33 double odom_pos_y = 0;
34 
35 uint8_t remote_buttons[8];
36 uint8_t remote_analog[8];
37 
41 
42 boost::mutex ros_mutex;
43 bool can_running = false;
44 
45 int can_open(const char * device)
46 {
47  struct ifreq ifr;
48  struct sockaddr_can addr;
49  /* open socket */
50  can_socket = socket(PF_CAN, SOCK_RAW, CAN_RAW);
51  if(can_socket < 0)
52  {
53  return (-1);
54  }
55  addr.can_family = AF_CAN;
56  strcpy(ifr.ifr_name, device);
57 
58  if (ioctl(can_socket, SIOCGIFINDEX, &ifr) < 0)
59  {
60  return (-2);
61  }
62  addr.can_ifindex = ifr.ifr_ifindex;
63  //fcntl(can_socket, F_SETFL, O_NONBLOCK);
64 
65 
66  if (bind(can_socket, (struct sockaddr *)&addr, sizeof(addr)) < 0)
67  {
68  return (-3);
69  }
70 
71  struct timeval tv;
72  tv.tv_sec = 1; // 1 second timeout
73  tv.tv_usec = 0; // Not init'ing this can cause strange errors
74  setsockopt(can_socket, SOL_SOCKET, SO_RCVTIMEO, (const char*)&tv,sizeof(struct timeval));
75 
76  return 0;
77 }
78 
79 int can_send_frame(struct can_frame * frame)
80 {
81  int retval;
82  retval = write(can_socket, frame, sizeof(struct can_frame));
83  if (retval != sizeof(struct can_frame))
84  {
85  return (-1);
86  }
87  else
88  {
89  return (0);
90  }
91 }
92 
93 int can_send_cmd_vel(double speed, double yawspeed, int modestate = 3)
94 {
95  struct can_frame msg_send;
96 
97  msg_send.can_id = 200;
98  msg_send.can_dlc = 5;
99 
100  int int_speed = speed * 100;
101  int int_yaw = yawspeed * 100;
102  msg_send.data[0] = int_speed;
103  msg_send.data[1] = int_speed >> 8;
104  msg_send.data[2] = int_yaw;
105  msg_send.data[3] = int_yaw >> 8;
106  msg_send.data[4] = modestate;
107 
108  can_send_frame(&msg_send);
109 }
110 
111 
113 {
114  struct can_frame frame_rd;
115  while(read(can_socket, &frame_rd, sizeof(struct can_frame))>0)
116  {
117  // Remote Control Values
118  if (frame_rd.can_id == 0x1E4)
119  {
120  for (int i = 0; i < 8; i++)
121  remote_analog[i] = frame_rd.data[i];
122  }
123  else if(frame_rd.can_id == 0x2E4) // Switches
124  {
125  for (int i = 0; i < 8; i++)
126  remote_buttons[i] = frame_rd.data[i];
127  publishJoyMsg();
128  }
129  else if (frame_rd.can_id == 235)
130  {
131  battery_voltage = (frame_rd.data[1]|(frame_rd.data[2]<<8))*0.01;
133  }
134  else if (frame_rd.can_id == 236)
135  {
136  odom_pos_x = (frame_rd.data[0]|(frame_rd.data[1]<<8)|(frame_rd.data[2]<<16)|(frame_rd.data[3]<<24))*0.001;
137  odom_pos_y = (frame_rd.data[4]|(frame_rd.data[5]<<8)|(frame_rd.data[6]<<16)|(frame_rd.data[7]<<24))*0.001;
138  }
139  else if (frame_rd.can_id == 237)
140  {
141  odom_orientation = (frame_rd.data[0]|(frame_rd.data[1]<<8)|(frame_rd.data[2]<<16)|(frame_rd.data[3]<<24))*0.001;
142  publishOdomMsg();
143  }
144  }
145 }
146 
148 {
149  static tf::TransformBroadcaster tf_br;
150 
151  geometry_msgs::Quaternion odom_quaternion = tf::createQuaternionMsgFromYaw(odom_orientation);
152 
153  nav_msgs::Odometry odom_msg;
154  odom_msg.header.stamp = ros::Time::now();
155  odom_msg.header.frame_id = "odom";
156  odom_msg.child_frame_id = "base_link";
157  odom_msg.pose.pose.position.x = odom_pos_x;
158  odom_msg.pose.pose.position.y = odom_pos_y;
159  odom_msg.pose.pose.orientation = odom_quaternion;
160 
161 
162  double odom_covariance[] = {0.1, 0, 0, 0, 0, 0,
163  0, 0.1, 0, 0, 0, 0,
164  0, 0, 9999.0, 0, 0, 0,
165  0, 0, 0, 0.6, 0, 0,
166  0, 0, 0, 0, 0.6, 0,
167  0, 0, 0, 0, 0, 0.1};
168  for(int i=0; i<36; i++)
169  {
170  odom_msg.pose.covariance[i] = odom_covariance[i];
171  }
172 
173  // Publish odometry message
174  publisherOdom.publish(odom_msg);
175 
176  // Also publish tf if necessary
177  geometry_msgs::TransformStamped odom_trans;
178  odom_trans.header.stamp = odom_msg.header.stamp;
179  odom_trans.header.frame_id = odom_msg.header.frame_id;
180  odom_trans.child_frame_id = odom_msg.child_frame_id;
181 
182  odom_trans.transform.translation.x = odom_pos_x;
183  odom_trans.transform.translation.y = odom_pos_y;
184  odom_trans.transform.translation.z = 0.0;
185  odom_trans.transform.rotation = odom_quaternion;
186 
187  ros_mutex.lock();
188  tf_br.sendTransform(odom_trans);
189  ros_mutex.unlock();
190 }
191 
193 {
194  std_msgs::Float32 voltage_msg;
195  voltage_msg.data = battery_voltage;
196  ros_mutex.lock();
197  publisherVoltage.publish(voltage_msg);
198  ros_mutex.unlock();
199 }
200 
202 {
203  sensor_msgs::Joy rc_msg;
204 
205  // analog axes
206  for(int i=0; i<=8; i++)
207  {
208  rc_msg.axes.push_back( (remote_analog[i] - 127) / 127.0);
209  }
210 
211  // buttons
212  for(int i=0; i<=8; i++)
213  {
214  for(int bit=0; bit<=8; bit++)
215  {
216  if(remote_buttons[i] & (1 << bit))
217  rc_msg.buttons.push_back(bool(true));
218  else
219  rc_msg.buttons.push_back(bool(false));
220  }
221  }
222  ros_mutex.lock();
223  publisherJoy.publish(rc_msg);
224  ros_mutex.unlock();
225 }
226 
227 void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& msg)
228 {
229  ROS_DEBUG("received cmd_vel s=%f y=%f", msg->linear.x, msg->angular.z);
230  can_send_cmd_vel(msg->linear.x, msg->angular.z);
231 }
232 
233 void can_task()
234 {
235  can_running = true;
236  while(can_running)
237  {
238  can_read_frames();
239  }
240 }
241 
242 int main(int argc, char **argv)
243 {
244  ros::init(argc, argv, "innok_heros_can_driver");
245  ros::NodeHandle n;
246  ros::Subscriber Sub = n.subscribe("cmd_vel", 10, cmdVelCallback);
247 
248  publisherOdom = n.advertise<nav_msgs::Odometry>("odom", 20);
249  publisherVoltage = n.advertise<std_msgs::Float32>("battery_voltage", 1);
250  publisherJoy = n.advertise<sensor_msgs::Joy>("remote_joy", 1);
251 
252  can_open("can0"); // TODO: parameter for can device
253 
254  boost::thread can_thread(can_task);
255 
256  ros::Rate loop_rate(1000);
257  while (ros::ok())
258  {
259  ros_mutex.lock();
260  ros::spinOnce();
261  ros_mutex.unlock();
262  loop_rate.sleep();
263  }
264  can_running = false;
265  return 0;
266 }
int can_send_cmd_vel(double speed, double yawspeed, int modestate=3)
void publish(const boost::shared_ptr< M > &message) const
double battery_voltage
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
uint8_t remote_buttons[8]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double odom_pos_x
double odom_orientation
double odom_pos_y
void can_read_frames()
boost::mutex ros_mutex
bool can_running
void publishJoyMsg()
ros::Publisher publisherOdom
void can_task()
ROSCPP_DECL bool ok()
int can_open(const char *device)
void sendTransform(const StampedTransform &transform)
int can_socket
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
void publishOdomMsg()
void publishVoltageMsg()
uint8_t remote_analog[8]
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &msg)
static Time now()
int can_send_frame(struct can_frame *frame)
ros::Publisher publisherJoy
ROSCPP_DECL void spinOnce()
ros::Publisher publisherVoltage
#define ROS_DEBUG(...)
int main(int argc, char **argv)


innok_heros_driver
Author(s): Alwin Heerklotz
autogenerated on Mon Jun 10 2019 13:39:12