54 can_msgs::Frame m = *msg.get();
65 ROS_ERROR(
"Invalid frame from topic: id: %#04x, length: %d, is_extended: %d", m.id, m.dlc, m.is_extended);
can::StateListenerConstSharedPtr state_listener_
std::string tostring(const Header &h, bool lc)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
can::DriverInterfaceSharedPtr driver_
TopicToSocketCAN(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
void convertMessageToSocketCAN(const can_msgs::Frame &m, can::Frame &f)
ros::Subscriber can_topic_
void stateCallback(const can::State &s)
unsigned int internal_error
void msgCallback(const can_msgs::Frame::ConstPtr &msg)
boost::system::error_code error_code