Go to the documentation of this file.
28 #ifndef SOCKETCAN_BRIDGE_SOCKETCAN_TO_TOPIC_H
29 #define SOCKETCAN_BRIDGE_SOCKETCAN_TO_TOPIC_H
33 #include <can_msgs/Frame.h>
63 m.is_error =
f.is_error;
65 m.is_extended =
f.is_extended;
67 for (
int i = 0; i < 8; i++)
69 m.data[i] =
f.data[i];
76 #endif // SOCKETCAN_BRIDGE_SOCKETCAN_TO_TOPIC_H
StateInterface::StateListenerConstSharedPtr StateListenerConstSharedPtr
SocketCANToTopic(ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver)
void frameCallback(const can::Frame &f)
void stateCallback(const can::State &s)
std::shared_ptr< DriverInterface > DriverInterfaceSharedPtr
std::vector< FrameFilterSharedPtr > FilterVector
can::StateListenerConstSharedPtr state_listener_
can::FrameListenerConstSharedPtr frame_listener_
can::DriverInterfaceSharedPtr driver_
ros::Publisher can_topic_
void convertSocketCANToMessage(const can::Frame &f, can_msgs::Frame &m)
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Wed Mar 2 2022 00:52:33