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 #include <ros/ros.h>
00036 #include <ros/package.h>
00037 #include "CanExtractor.h"
00038 #include <can_msgs/Frame.h>
00039
00040 ros::NodeHandle *nh_;
00041 dataspeed_can_tools::CanExtractor* extractor_;
00042
00043 void recv(const can_msgs::Frame::ConstPtr& msg)
00044 {
00045 if (!msg->is_error && !msg->is_rtr) {
00046 dataspeed_can_tools::RosCanMsgStruct info;
00047 info.id = msg->id | (msg->is_extended ? 0x80000000 : 0x00000000);
00048
00049 if (extractor_->getMessage(info)) {
00050 ROS_DEBUG("New message ID (%d), initializing publishers...", info.id);
00051 extractor_->initPublishers(info, *nh_);
00052 }
00053
00054 extractor_->pubMessage(msg);
00055 }
00056 }
00057
00058 int main(int argc, char** argv)
00059 {
00060 ros::init(argc, argv, "can_parser_node");
00061 ros::NodeHandle nh; nh_ = &nh;
00062 ros::NodeHandle nh_priv("~");
00063
00064 std::vector<std::string> dbc_files;
00065 if (!nh_priv.getParam("dbc_files", dbc_files)) {
00066 ROS_FATAL("DBC file not specified. Exiting.");
00067 }
00068 bool expand;
00069 nh_priv.param("expand", expand, true);
00070 bool unknown;
00071 nh_priv.param("unknown", unknown, false);
00072
00073 printf("Opening dbc files: \n");
00074 for (unsigned int i = 0; i < dbc_files.size(); i++) {
00075 printf(" - %s\n", dbc_files[i].c_str());
00076 }
00077 dataspeed_can_tools::CanExtractor extractor(dbc_files, false, expand, unknown);
00078 extractor_ = &extractor;
00079
00080 ros::Subscriber sub_can = nh.subscribe("can_rx", 100, recv);
00081
00082 ros::spin();
00083 }
00084