38 #include <can_msgs/Frame.h> 43 void recv(
const can_msgs::Frame::ConstPtr& msg)
45 if (!msg->is_error && !msg->is_rtr) {
47 info.
id = msg->id | (msg->is_extended ? 0x80000000 : 0x00000000);
50 ROS_DEBUG(
"New message ID (%d), initializing publishers...", info.
id);
58 int main(
int argc,
char** argv)
64 std::vector<std::string> dbc_files;
65 if (!nh_priv.
getParam(
"dbc_files", dbc_files)) {
66 ROS_FATAL(
"DBC file not specified. Exiting.");
69 nh_priv.
param(
"expand", expand,
true);
71 nh_priv.
param(
"unknown", unknown,
false);
73 printf(
"Opening dbc files: \n");
74 for (
unsigned int i = 0; i < dbc_files.size(); i++) {
75 printf(
" - %s\n", dbc_files[i].c_str());
78 extractor_ = &extractor;
dataspeed_can_tools::CanExtractor * extractor_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void recv(const can_msgs::Frame::ConstPtr &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int main(int argc, char **argv)
bool getParam(const std::string &key, std::string &s) const