#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 dataspeed_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)) |
|
void | pubMessage (const dataspeed_can_msgs::Frame::ConstPtr &msg, const ros::Time &stamp=ros::Time(0)) |
|
|
void | pubCanMsg (const RosCanMsgStruct &info, const can_msgs::Frame &msg, const ros::Time &stamp) |
|
void | pubCanMsg (const RosCanMsgStruct &info, const dataspeed_can_msgs::Frame &msg, const ros::Time &stamp) |
|
void | pubCanMsgSignals (const RosCanMsgStruct &info, const std::vector< uint8_t > &buffer, 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) |
|
Definition at line 82 of file CanExtractor.h.
◆ CanExtractor() [1/2]
dataspeed_can_tools::CanExtractor::CanExtractor |
( |
const std::string & |
dbc_file, |
|
|
bool |
offline, |
|
|
bool |
expand = true , |
|
|
bool |
unknown = false |
|
) |
| |
◆ CanExtractor() [2/2]
dataspeed_can_tools::CanExtractor::CanExtractor |
( |
const std::vector< std::string > & |
dbc_file, |
|
|
bool |
offline, |
|
|
bool |
expand = true , |
|
|
bool |
unknown = false |
|
) |
| |
◆ buildMsg()
template<class T >
T dataspeed_can_tools::CanExtractor::buildMsg |
( |
const RosCanSigStruct & |
info, |
|
|
const std::vector< uint8_t > & |
buffer, |
|
|
bool |
sign |
|
) |
| |
|
staticprivate |
◆ closeBag()
bool dataspeed_can_tools::CanExtractor::closeBag |
( |
| ) |
|
◆ getAppropriateSize()
int dataspeed_can_tools::CanExtractor::getAppropriateSize |
( |
const RosCanSigStruct & |
sig_props, |
|
|
bool |
output_signed |
|
) |
| |
|
staticprivate |
◆ getMessage()
bool dataspeed_can_tools::CanExtractor::getMessage |
( |
RosCanMsgStruct & |
can_msg | ) |
|
◆ initPublishers()
◆ openBag()
◆ pubCanMsg() [1/2]
void dataspeed_can_tools::CanExtractor::pubCanMsg |
( |
const RosCanMsgStruct & |
info, |
|
|
const can_msgs::Frame & |
msg, |
|
|
const ros::Time & |
stamp |
|
) |
| |
|
private |
◆ pubCanMsg() [2/2]
void dataspeed_can_tools::CanExtractor::pubCanMsg |
( |
const RosCanMsgStruct & |
info, |
|
|
const dataspeed_can_msgs::Frame & |
msg, |
|
|
const ros::Time & |
stamp |
|
) |
| |
|
private |
◆ pubCanMsgSignals()
void dataspeed_can_tools::CanExtractor::pubCanMsgSignals |
( |
const RosCanMsgStruct & |
info, |
|
|
const std::vector< uint8_t > & |
buffer, |
|
|
const ros::Time & |
stamp |
|
) |
| |
|
private |
◆ pubCanSig()
template<class T >
void dataspeed_can_tools::CanExtractor::pubCanSig |
( |
const RosCanMsgStruct & |
info, |
|
|
const T & |
sig_msg, |
|
|
const ros::Time & |
stamp, |
|
|
size_t |
i |
|
) |
| |
|
private |
◆ pubMessage() [1/4]
void dataspeed_can_tools::CanExtractor::pubMessage |
( |
const can_msgs::Frame & |
msg, |
|
|
const ros::Time & |
stamp = ros::Time(0) |
|
) |
| |
◆ pubMessage() [2/4]
void dataspeed_can_tools::CanExtractor::pubMessage |
( |
const dataspeed_can_msgs::Frame & |
msg, |
|
|
const ros::Time & |
stamp = ros::Time(0) |
|
) |
| |
◆ pubMessage() [3/4]
void dataspeed_can_tools::CanExtractor::pubMessage |
( |
const can_msgs::Frame::ConstPtr & |
msg, |
|
|
const ros::Time & |
stamp = ros::Time(0) |
|
) |
| |
|
inline |
◆ pubMessage() [4/4]
void dataspeed_can_tools::CanExtractor::pubMessage |
( |
const dataspeed_can_msgs::Frame::ConstPtr & |
msg, |
|
|
const ros::Time & |
stamp = ros::Time(0) |
|
) |
| |
|
inline |
◆ registerCanSignalPublisher()
◆ signedSignalData()
int64_t dataspeed_can_tools::CanExtractor::signedSignalData |
( |
const std::vector< uint8_t > & |
buffer, |
|
|
const RosCanSigStruct & |
sig_props |
|
) |
| |
|
staticprivate |
◆ unsignedSignalData()
uint64_t dataspeed_can_tools::CanExtractor::unsignedSignalData |
( |
const std::vector< uint8_t > & |
buffer, |
|
|
const RosCanSigStruct & |
sig_props |
|
) |
| |
|
staticprivate |
◆ writeToBag()
template<class T >
void dataspeed_can_tools::CanExtractor::writeToBag |
( |
const std::string & |
frame, |
|
|
const ros::Time & |
stamp, |
|
|
const T & |
msg |
|
) |
| |
|
private |
◆ bag_
◆ bag_fname_
std::string dataspeed_can_tools::CanExtractor::bag_fname_ |
|
private |
◆ bag_open_
bool dataspeed_can_tools::CanExtractor::bag_open_ |
|
private |
◆ dbc_
◆ expand_
bool dataspeed_can_tools::CanExtractor::expand_ |
|
private |
◆ msgs_
std::map<uint32_t, RosCanMsgStruct> dataspeed_can_tools::CanExtractor::msgs_ |
|
private |
◆ offline_
bool dataspeed_can_tools::CanExtractor::offline_ |
|
private |
◆ unknown_
bool dataspeed_can_tools::CanExtractor::unknown_ |
|
private |
◆ unknown_msgs_
std::map<uint32_t, int> dataspeed_can_tools::CanExtractor::unknown_msgs_ |
|
private |
The documentation for this class was generated from the following files: