Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <iostream>
00039
00040 #include <ros/ros.h>
00041 #include <can_msgs/CANFrame.h>
00042
00043 #include "USB2_F_7001.h"
00044
00045 USB2_F_7001 * can_usb_adapter;
00046
00047 ros::Publisher rx_pub;
00048
00049 void CANFrameToSend(const can_msgs::CANFrame::ConstPtr& msg)
00050 {
00051 char buffer[5];
00052
00053 sprintf(buffer, "%03X%d", msg->cob_id, (int)msg->data.size());
00054
00055 std::string frame = buffer;
00056 for(int i=0 ; i<msg->data.size() ; i++)
00057 {
00058 sprintf(buffer, "%02X", msg->data[i]);
00059 frame.append(buffer);
00060 }
00061
00062 ROS_INFO("USB2_F_7001 - %s - Sending CAN Frame: %s", __FUNCTION__, frame.c_str());
00063
00064 can_usb_adapter->transmitStandardFrame(&frame);
00065 }
00066
00067 void CANFrameReceived(std::string * frame)
00068 {
00069 ROS_INFO("USB2_F_7001 - %s - Received CAN Frame: %s", __FUNCTION__, frame->c_str());
00070
00071 char cob_id_string[4];
00072 frame->copy(cob_id_string, 3, 1);
00073 int cob_id;
00074 sscanf(cob_id_string, "%X", &cob_id);
00075
00076 ROS_INFO("USB2_F_7001 - %s - COB ID %s %d", __FUNCTION__, cob_id_string, cob_id);
00077
00078 int data_size = (frame->length()-5)/2;
00079
00080 can_msgs::CANFrame frame_msg;
00081 frame_msg.stamp = ros::Time::now();
00082 frame_msg.cob_id = cob_id;
00083
00084 char buffer[3];
00085 int byte;
00086 frame_msg.data.resize(data_size);
00087 for(int i=0 ; i<data_size ; i++)
00088 {
00089 frame->copy(buffer, 2, 5+i*2);
00090 sscanf(buffer, "%X", &byte);
00091 frame_msg.data[i] = byte;
00092 }
00093
00094 rx_pub.publish(frame_msg);
00095 }
00096
00097 int main(int argc, char** argv)
00098 {
00099 ros::init(argc, argv, "USB2_F_7001_node");
00100 ros::NodeHandle n;
00101 ros::NodeHandle pn("~");
00102
00103 rx_pub = n.advertise<can_msgs::CANFrame>("/can_bus_rx", 10);
00104 ros::Subscriber tx_sub = n.subscribe<can_msgs::CANFrame>("/can_bus_tx", 10, CANFrameToSend);
00105
00106 std::string port;
00107 pn.param<std::string>("port", port, "/dev/tty.USB0");
00108 int bit_rate;
00109 pn.param("bit_rate", bit_rate, 5);
00110
00111 can_usb_adapter = new USB2_F_7001(&port, &CANFrameReceived);
00112
00113 ROS_INFO("USB2_F_7001 -- Opening CAN bus...");
00114 if( !can_usb_adapter->openCANBus(bit_rate) )
00115 {
00116 ROS_FATAL("USB2_F_7001 -- Failed to open the CAN bus!");
00117 ROS_BREAK();
00118 }
00119 ROS_INFO("USB2_F_7001 -- The CAN bus is now open!");
00120
00121 ros::spin();
00122
00123 delete can_usb_adapter;
00124
00125 return(0);
00126 }
00127
00128
00129