Go to the documentation of this file.00001 #include <string>
00002 #include "ros/ros.h"
00003 #include "std_msgs/String.h"
00004 #include "tinycan/CanMsg.h"
00005 #include "can_drv.h"
00006 #include "can_core.h"
00007
00008 using std::string;
00009
00010 int main (int argc, char **argv)
00011 {
00012 TCanMsg can_msg;
00013 tinycan::Can *can_dev = new tinycan::Can();
00014
00015 string pub_topic_raw;
00016 string sub_topic_raw;
00017
00018 if (!can_dev->init()) {
00019 return 0;
00020 }
00021
00022 ros::init(argc, argv, "can");
00023
00024 ros::NodeHandle n;
00025
00026
00027 ros::NodeHandle private_node_handle_("~");
00028 private_node_handle_.param("pub_topic_raw", pub_topic_raw, string("/can_raw_receive"));
00029 private_node_handle_.param("sub_topic_raw", sub_topic_raw, string("/can_raw_send"));
00030
00031
00032 ros::Publisher pub_can_message = n.advertise<tinycan::CanMsg>(pub_topic_raw.c_str(), 50);
00033
00034 ros::Subscriber sub_message = n.subscribe(sub_topic_raw.c_str(), 1000, &tinycan::Can::callbackCanMessage, can_dev);
00035
00036 ros::Rate loop_rate(50);
00037 int count = 0;
00038
00039 while (ros::ok()) {
00040
00041 while (can_dev->readMsg(&can_msg)) {
00042
00043 can_dev->publishCanMessage(&pub_can_message, &can_msg);
00044 }
00045
00046
00047 ros::spinOnce();
00048 loop_rate.sleep();
00049 ++count;
00050 }
00051 return 0;
00052 }