#include <CanExtractor.h>
Public Member Functions | |
| CanExtractor (const std::string &dbc_file, bool offline, bool expand=true, bool unknown=false) | |
| CanExtractor (const std::vector< std::string > &dbc_file, bool offline, bool expand=true, bool unknown=false) | |
| bool | closeBag () |
| bool | getMessage (RosCanMsgStruct &can_msg) |
| void | initPublishers (RosCanMsgStruct &info, ros::NodeHandle &nh) |
| bool | openBag (const std::string &fname, rosbag::compression::CompressionType compression=rosbag::compression::Uncompressed) |
| void | pubMessage (const can_msgs::Frame &msg, const ros::Time &stamp=ros::Time(0)) |
| void | pubMessage (const can_msgs::Frame::ConstPtr &msg, const ros::Time &stamp=ros::Time(0)) |
Private Member Functions | |
| void | pubCanMsg (const RosCanMsgStruct &info, const can_msgs::Frame &msg, const ros::Time &stamp) |
| template<class T > | |
| void | pubCanSig (const RosCanMsgStruct &info, const T &sig_msg, const ros::Time &stamp, size_t i) |
| template<class T > | |
| void | writeToBag (const std::string &frame, const ros::Time &stamp, const T &msg) |
Static Private Member Functions | |
| template<class T > | |
| static T | buildMsg (const RosCanSigStruct &info, const uint64_t &data, bool sign) |
| static int | getAppropriateSize (const RosCanSigStruct &sig_props, bool output_signed) |
| static void | registerCanSignalPublisher (RosCanSigStruct &info, ros::NodeHandle &nh) |
| static int64_t | signedSignalData (uint64_t raw_data, const RosCanSigStruct &sig_props) |
| static uint64_t | unsignedSignalData (uint64_t raw_data, const RosCanSigStruct &sig_props) |
Private Attributes | |
| rosbag::Bag | bag_ |
| std::string | bag_fname_ |
| bool | bag_open_ |
| DBCIterator | dbc_ |
| bool | expand_ |
| std::map< uint32_t, RosCanMsgStruct > | msgs_ |
| bool | offline_ |
| bool | unknown_ |
| std::map< uint32_t, int > | unknown_msgs_ |
Definition at line 81 of file CanExtractor.h.
| dataspeed_can_tools::CanExtractor::CanExtractor | ( | const std::string & | dbc_file, |
| bool | offline, | ||
| bool | expand = true, |
||
| bool | unknown = false |
||
| ) |
Definition at line 39 of file CanExtractor.cpp.
| dataspeed_can_tools::CanExtractor::CanExtractor | ( | const std::vector< std::string > & | dbc_file, |
| bool | offline, | ||
| bool | expand = true, |
||
| bool | unknown = false |
||
| ) |
Definition at line 47 of file CanExtractor.cpp.
| T dataspeed_can_tools::CanExtractor::buildMsg | ( | const RosCanSigStruct & | info, |
| const uint64_t & | data, | ||
| bool | sign | ||
| ) | [static, private] |
Definition at line 98 of file CanExtractor.cpp.
Definition at line 226 of file CanExtractor.cpp.
| int dataspeed_can_tools::CanExtractor::getAppropriateSize | ( | const RosCanSigStruct & | sig_props, |
| bool | output_signed | ||
| ) | [static, private] |
Definition at line 109 of file CanExtractor.cpp.
| bool dataspeed_can_tools::CanExtractor::getMessage | ( | RosCanMsgStruct & | can_msg | ) |
Definition at line 153 of file CanExtractor.cpp.
| void dataspeed_can_tools::CanExtractor::initPublishers | ( | RosCanMsgStruct & | info, |
| ros::NodeHandle & | nh | ||
| ) |
Definition at line 199 of file CanExtractor.cpp.
| bool dataspeed_can_tools::CanExtractor::openBag | ( | const std::string & | fname, |
| rosbag::compression::CompressionType | compression = rosbag::compression::Uncompressed |
||
| ) |
Definition at line 215 of file CanExtractor.cpp.
| void dataspeed_can_tools::CanExtractor::pubCanMsg | ( | const RosCanMsgStruct & | info, |
| const can_msgs::Frame & | msg, | ||
| const ros::Time & | stamp | ||
| ) | [private] |
Definition at line 285 of file CanExtractor.cpp.
| void dataspeed_can_tools::CanExtractor::pubCanSig | ( | const RosCanMsgStruct & | info, |
| const T & | sig_msg, | ||
| const ros::Time & | stamp, | ||
| size_t | i | ||
| ) | [private] |
Definition at line 274 of file CanExtractor.cpp.
| void dataspeed_can_tools::CanExtractor::pubMessage | ( | const can_msgs::Frame & | msg, |
| const ros::Time & | stamp = ros::Time(0) |
||
| ) |
Definition at line 293 of file CanExtractor.cpp.
| void dataspeed_can_tools::CanExtractor::pubMessage | ( | const can_msgs::Frame::ConstPtr & | msg, |
| const ros::Time & | stamp = ros::Time(0) |
||
| ) | [inline] |
Definition at line 91 of file CanExtractor.h.
| void dataspeed_can_tools::CanExtractor::registerCanSignalPublisher | ( | RosCanSigStruct & | info, |
| ros::NodeHandle & | nh | ||
| ) | [static, private] |
Definition at line 236 of file CanExtractor.cpp.
| int64_t dataspeed_can_tools::CanExtractor::signedSignalData | ( | uint64_t | raw_data, |
| const RosCanSigStruct & | sig_props | ||
| ) | [static, private] |
Definition at line 78 of file CanExtractor.cpp.
| uint64_t dataspeed_can_tools::CanExtractor::unsignedSignalData | ( | uint64_t | raw_data, |
| const RosCanSigStruct & | sig_props | ||
| ) | [static, private] |
Definition at line 55 of file CanExtractor.cpp.
| void dataspeed_can_tools::CanExtractor::writeToBag | ( | const std::string & | frame, |
| const ros::Time & | stamp, | ||
| const T & | msg | ||
| ) | [private] |
Definition at line 263 of file CanExtractor.cpp.
Definition at line 107 of file CanExtractor.h.
std::string dataspeed_can_tools::CanExtractor::bag_fname_ [private] |
Definition at line 109 of file CanExtractor.h.
bool dataspeed_can_tools::CanExtractor::bag_open_ [private] |
Definition at line 108 of file CanExtractor.h.
Definition at line 106 of file CanExtractor.h.
bool dataspeed_can_tools::CanExtractor::expand_ [private] |
Definition at line 111 of file CanExtractor.h.
std::map<uint32_t, RosCanMsgStruct> dataspeed_can_tools::CanExtractor::msgs_ [private] |
Definition at line 114 of file CanExtractor.h.
bool dataspeed_can_tools::CanExtractor::offline_ [private] |
Definition at line 110 of file CanExtractor.h.
bool dataspeed_can_tools::CanExtractor::unknown_ [private] |
Definition at line 112 of file CanExtractor.h.
std::map<uint32_t, int> dataspeed_can_tools::CanExtractor::unknown_msgs_ [private] |
Definition at line 115 of file CanExtractor.h.