28 #ifndef SOCKETCAN_BRIDGE_TOPIC_TO_SOCKETCAN_H 29 #define SOCKETCAN_BRIDGE_TOPIC_TO_SOCKETCAN_H 32 #include <can_msgs/Frame.h> 49 void msgCallback(
const can_msgs::Frame::ConstPtr& msg);
61 for (
int i = 0; i < 8; i++)
63 f.
data[i] = m.data[i];
70 #endif // SOCKETCAN_BRIDGE_TOPIC_TO_SOCKETCAN_H
can::StateListenerConstSharedPtr state_listener_
can::DriverInterfaceSharedPtr driver_
TopicToSocketCAN(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
boost::array< value_type, 8 > data
void convertMessageToSocketCAN(const can_msgs::Frame &m, can::Frame &f)
ros::Subscriber can_topic_
void stateCallback(const can::State &s)
void msgCallback(const can_msgs::Frame::ConstPtr &msg)