9 #include <linux/can/raw.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> 48 struct sockaddr_can addr;
50 can_socket = socket(PF_CAN, SOCK_RAW, CAN_RAW);
55 addr.can_family = AF_CAN;
56 strcpy(ifr.ifr_name, device);
58 if (ioctl(can_socket, SIOCGIFINDEX, &ifr) < 0)
62 addr.can_ifindex = ifr.ifr_ifindex;
66 if (bind(can_socket, (
struct sockaddr *)&addr,
sizeof(addr)) < 0)
74 setsockopt(can_socket, SOL_SOCKET, SO_RCVTIMEO, (
const char*)&tv,
sizeof(
struct timeval));
82 retval = write(
can_socket, frame,
sizeof(
struct can_frame));
83 if (retval !=
sizeof(
struct can_frame))
95 struct can_frame msg_send;
97 msg_send.can_id = 200;
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;
114 struct can_frame frame_rd;
115 while(read(
can_socket, &frame_rd,
sizeof(
struct can_frame))>0)
118 if (frame_rd.can_id == 0x1E4)
120 for (
int i = 0; i < 8; i++)
123 else if(frame_rd.can_id == 0x2E4)
125 for (
int i = 0; i < 8; i++)
129 else if (frame_rd.can_id == 235)
134 else if (frame_rd.can_id == 236)
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;
139 else if (frame_rd.can_id == 237)
141 odom_orientation = (frame_rd.data[0]|(frame_rd.data[1]<<8)|(frame_rd.data[2]<<16)|(frame_rd.data[3]<<24))*0.001;
153 nav_msgs::Odometry odom_msg;
155 odom_msg.header.frame_id =
"odom";
156 odom_msg.child_frame_id =
"base_link";
159 odom_msg.pose.pose.orientation = odom_quaternion;
162 double odom_covariance[] = {0.1, 0, 0, 0, 0, 0,
164 0, 0, 9999.0, 0, 0, 0,
168 for(
int i=0; i<36; i++)
170 odom_msg.pose.covariance[i] = odom_covariance[i];
174 publisherOdom.
publish(odom_msg);
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;
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;
194 std_msgs::Float32 voltage_msg;
197 publisherVoltage.
publish(voltage_msg);
203 sensor_msgs::Joy rc_msg;
206 for(
int i=0; i<=8; i++)
212 for(
int i=0; i<=8; i++)
214 for(
int bit=0; bit<=8; bit++)
217 rc_msg.buttons.push_back(
bool(
true));
219 rc_msg.buttons.push_back(
bool(
false));
229 ROS_DEBUG(
"received cmd_vel s=%f y=%f", msg->linear.x, msg->angular.z);
242 int main(
int argc,
char **argv)
244 ros::init(argc, argv,
"innok_heros_can_driver");
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);
int can_send_cmd_vel(double speed, double yawspeed, int modestate=3)
void publish(const boost::shared_ptr< M > &message) const
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)
ros::Publisher publisherOdom
int can_open(const char *device)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &msg)
int can_send_frame(struct can_frame *frame)
ros::Publisher publisherJoy
ROSCPP_DECL void spinOnce()
ros::Publisher publisherVoltage
int main(int argc, char **argv)