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 #ifndef CANEXTRACTOR_H_
00036 #define CANEXTRACTOR_H_
00037
00038 #include <ros/ros.h>
00039 #include <rosbag/bag.h>
00040 #include <ros/package.h>
00041
00042 #include <std_msgs/Bool.h>
00043 #include <std_msgs/UInt8.h>
00044 #include <std_msgs/UInt16.h>
00045 #include <std_msgs/UInt32.h>
00046 #include <std_msgs/UInt64.h>
00047 #include <std_msgs/Int8.h>
00048 #include <std_msgs/Int16.h>
00049 #include <std_msgs/Int32.h>
00050 #include <std_msgs/Int64.h>
00051 #include <std_msgs/Float64.h>
00052
00053 #include <can_msgs/Frame.h>
00054 #include "DbcIterator.hpp"
00055
00056 namespace dataspeed_can_tools
00057 {
00058
00059 typedef struct {
00060 ros::Publisher sig_pub;
00061 double factor;
00062 int length;
00063 double maximum;
00064 double minimum;
00065 std::string sig_name;
00066 double offset;
00067 ByteOrder order;
00068 Sign sign;
00069 int start_bit;
00070 Multiplexor multiplexor;
00071 unsigned short multiplexNum;
00072 } RosCanSigStruct;
00073
00074 typedef struct {
00075 ros::Publisher message_pub;
00076 std::string msg_name;
00077 uint32_t id;
00078 std::vector<RosCanSigStruct> sigs;
00079 } RosCanMsgStruct;
00080
00081 class CanExtractor {
00082 public:
00083 CanExtractor(const std::string &dbc_file, bool offline, bool expand = true, bool unknown = false);
00084 CanExtractor(const std::vector<std::string> &dbc_file, bool offline, bool expand = true, bool unknown = false);
00085
00086 bool getMessage(RosCanMsgStruct& can_msg);
00087 void initPublishers(RosCanMsgStruct& info, ros::NodeHandle& nh);
00088 bool openBag(const std::string &fname, rosbag::compression::CompressionType compression = rosbag::compression::Uncompressed);
00089 bool closeBag();
00090 void pubMessage(const can_msgs::Frame& msg, const ros::Time &stamp = ros::Time(0));
00091 void pubMessage(const can_msgs::Frame::ConstPtr& msg, const ros::Time &stamp = ros::Time(0)) { pubMessage(*msg, stamp); }
00092
00093 private:
00094 template<class T>
00095 void writeToBag(const std::string& frame, const ros::Time& stamp, const T& msg);
00096 template<class T>
00097 void pubCanSig(const RosCanMsgStruct& info, const T& sig_msg, const ros::Time& stamp, size_t i);
00098 void pubCanMsg(const RosCanMsgStruct& info, const can_msgs::Frame& msg, const ros::Time& stamp);
00099 static uint64_t unsignedSignalData(uint64_t raw_data, const RosCanSigStruct& sig_props);
00100 static int64_t signedSignalData(uint64_t raw_data, const RosCanSigStruct& sig_props);
00101 template<class T>
00102 static T buildMsg(const RosCanSigStruct& info, const uint64_t& data, bool sign);
00103 static int getAppropriateSize(const RosCanSigStruct& sig_props, bool output_signed);
00104 static void registerCanSignalPublisher(RosCanSigStruct& info, ros::NodeHandle& nh);
00105
00106 DBCIterator dbc_;
00107 rosbag::Bag bag_;
00108 bool bag_open_;
00109 std::string bag_fname_;
00110 bool offline_;
00111 bool expand_;
00112 bool unknown_;
00113
00114 std::map<uint32_t, RosCanMsgStruct> msgs_;
00115 std::map<uint32_t, int> unknown_msgs_;
00116 };
00117
00118 }
00119
00120 #endif
00121