28 #ifndef SOCKETCAN_BRIDGE_SOCKETCAN_TO_TOPIC_H 29 #define SOCKETCAN_BRIDGE_SOCKETCAN_TO_TOPIC_H 33 #include <can_msgs/Frame.h> 67 for (
int i = 0; i < 8; i++)
69 m.data[i] = f.
data[i];
76 #endif // SOCKETCAN_BRIDGE_SOCKETCAN_TO_TOPIC_H
can::FrameListenerConstSharedPtr frame_listener_
SocketCANToTopic(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
boost::array< value_type, 8 > data
ros::Publisher can_topic_
can::DriverInterfaceSharedPtr driver_
std::vector< FrameFilterSharedPtr > FilterVector
void stateCallback(const can::State &s)
void frameCallback(const can::Frame &f)
void convertSocketCANToMessage(const can::Frame &f, can_msgs::Frame &m)
can::StateListenerConstSharedPtr state_listener_