#include <socketcan_to_topic.h>
Public Member Functions | |
void | setup () |
void | setup (const can::FilteredFrameListener::FilterVector &filters) |
void | setup (XmlRpc::XmlRpcValue filters) |
void | setup (ros::NodeHandle nh) |
SocketCANToTopic (ros::NodeHandle *nh, ros::NodeHandle *nh_param, can::DriverInterfaceSharedPtr driver) | |
Private Member Functions | |
void | frameCallback (const can::Frame &f) |
void | stateCallback (const can::State &s) |
Private Attributes | |
ros::Publisher | can_topic_ |
can::DriverInterfaceSharedPtr | driver_ |
can::FrameListenerConstSharedPtr | frame_listener_ |
can::StateListenerConstSharedPtr | state_listener_ |
Definition at line 38 of file socketcan_to_topic.h.
socketcan_bridge::SocketCANToTopic::SocketCANToTopic | ( | ros::NodeHandle * | nh, |
ros::NodeHandle * | nh_param, | ||
can::DriverInterfaceSharedPtr | driver | ||
) |
Definition at line 48 of file socketcan_to_topic.cpp.
|
private |
Definition at line 84 of file socketcan_to_topic.cpp.
void socketcan_bridge::SocketCANToTopic::setup | ( | ) |
Definition at line 55 of file socketcan_to_topic.cpp.
void socketcan_bridge::SocketCANToTopic::setup | ( | const can::FilteredFrameListener::FilterVector & | filters | ) |
Definition at line 65 of file socketcan_to_topic.cpp.
void socketcan_bridge::SocketCANToTopic::setup | ( | XmlRpc::XmlRpcValue | filters | ) |
Definition at line 74 of file socketcan_to_topic.cpp.
void socketcan_bridge::SocketCANToTopic::setup | ( | ros::NodeHandle | nh | ) |
Definition at line 77 of file socketcan_to_topic.cpp.
|
private |
Definition at line 114 of file socketcan_to_topic.cpp.
|
private |
Definition at line 48 of file socketcan_to_topic.h.
|
private |
Definition at line 49 of file socketcan_to_topic.h.
|
private |
Definition at line 51 of file socketcan_to_topic.h.
|
private |
Definition at line 52 of file socketcan_to_topic.h.