Go to the documentation of this file.
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);
57 f.is_error = m.is_error;
59 f.is_extended = m.is_extended;
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_
StateInterface::StateListenerConstSharedPtr StateListenerConstSharedPtr
std::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
can::DriverInterfaceSharedPtr driver_
ros::Subscriber can_topic_
void convertMessageToSocketCAN(const can_msgs::Frame &m, can::Frame &f)
void stateCallback(const can::State &s)
TopicToSocketCAN(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
void msgCallback(const can_msgs::Frame::ConstPtr &msg)
socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Wed Mar 2 2022 00:52:33