#include <CanExtractor.h>
|
| 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)) |
|
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 |
|
) |
| |
dataspeed_can_tools::CanExtractor::CanExtractor |
( |
const std::vector< std::string > & |
dbc_file, |
|
|
bool |
offline, |
|
|
bool |
expand = true , |
|
|
bool |
unknown = false |
|
) |
| |
template<class T >
T dataspeed_can_tools::CanExtractor::buildMsg |
( |
const RosCanSigStruct & |
info, |
|
|
const uint64_t & |
data, |
|
|
bool |
sign |
|
) |
| |
|
staticprivate |
bool dataspeed_can_tools::CanExtractor::closeBag |
( |
| ) |
|
int dataspeed_can_tools::CanExtractor::getAppropriateSize |
( |
const RosCanSigStruct & |
sig_props, |
|
|
bool |
output_signed |
|
) |
| |
|
staticprivate |
bool dataspeed_can_tools::CanExtractor::getMessage |
( |
RosCanMsgStruct & |
can_msg | ) |
|
void dataspeed_can_tools::CanExtractor::pubCanMsg |
( |
const RosCanMsgStruct & |
info, |
|
|
const can_msgs::Frame & |
msg, |
|
|
const ros::Time & |
stamp |
|
) |
| |
|
private |
template<class T >
void dataspeed_can_tools::CanExtractor::pubCanSig |
( |
const RosCanMsgStruct & |
info, |
|
|
const T & |
sig_msg, |
|
|
const ros::Time & |
stamp, |
|
|
size_t |
i |
|
) |
| |
|
private |
void dataspeed_can_tools::CanExtractor::pubMessage |
( |
const can_msgs::Frame & |
msg, |
|
|
const ros::Time & |
stamp = ros::Time(0) |
|
) |
| |
void dataspeed_can_tools::CanExtractor::pubMessage |
( |
const can_msgs::Frame::ConstPtr & |
msg, |
|
|
const ros::Time & |
stamp = ros::Time(0) |
|
) |
| |
|
inline |
int64_t dataspeed_can_tools::CanExtractor::signedSignalData |
( |
uint64_t |
raw_data, |
|
|
const RosCanSigStruct & |
sig_props |
|
) |
| |
|
staticprivate |
uint64_t dataspeed_can_tools::CanExtractor::unsignedSignalData |
( |
uint64_t |
raw_data, |
|
|
const RosCanSigStruct & |
sig_props |
|
) |
| |
|
staticprivate |
template<class T >
void dataspeed_can_tools::CanExtractor::writeToBag |
( |
const std::string & |
frame, |
|
|
const ros::Time & |
stamp, |
|
|
const T & |
msg |
|
) |
| |
|
private |
std::string dataspeed_can_tools::CanExtractor::bag_fname_ |
|
private |
bool dataspeed_can_tools::CanExtractor::bag_open_ |
|
private |
bool dataspeed_can_tools::CanExtractor::expand_ |
|
private |
std::map<uint32_t, RosCanMsgStruct> dataspeed_can_tools::CanExtractor::msgs_ |
|
private |
bool dataspeed_can_tools::CanExtractor::offline_ |
|
private |
bool dataspeed_can_tools::CanExtractor::unknown_ |
|
private |
std::map<uint32_t, int> dataspeed_can_tools::CanExtractor::unknown_msgs_ |
|
private |
The documentation for this class was generated from the following files: