30 #include <can_msgs/Frame.h> 37 uint32_t
id =
static_cast<int>(t);
41 return tofilter(static_cast<std::string>(t));
51 can_topic_ = nh->
advertise<can_msgs::Frame>(
"received_messages", 10);
55 void SocketCANToTopic::setup()
58 frame_listener_ = driver_->createMsgListener(
61 state_listener_ = driver_->createStateListener(
70 state_listener_ = driver_->createStateListener(
84 void SocketCANToTopic::frameCallback(
const can::Frame& f)
89 ROS_ERROR(
"Invalid frame from SocketCAN: id: %#04x, length: %d, is_extended: %d, is_error: %d, is_rtr: %d",
107 msg.header.frame_id =
"";
110 can_topic_.publish(msg);
FilteredFrameListener::FilterVector tofilters(const T &v)
std::string tostring(const Header &h, bool lc)
FrameFilterSharedPtr tofilter(const T &ct)
std::vector< FrameFilterSharedPtr > FilterVector
void convertSocketCANToMessage(const can::Frame &f, can_msgs::Frame &m)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getParam(const std::string &key, std::string &s) const
unsigned int internal_error
boost::system::error_code error_code