Public Member Functions | Private Member Functions | Private Attributes | List of all members
socketcan_bridge::SocketCANToTopic Class Reference

#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_
 

Detailed Description

Definition at line 38 of file socketcan_to_topic.h.

Constructor & Destructor Documentation

socketcan_bridge::SocketCANToTopic::SocketCANToTopic ( ros::NodeHandle nh,
ros::NodeHandle nh_param,
can::DriverInterfaceSharedPtr  driver 
)

Definition at line 48 of file socketcan_to_topic.cpp.

Member Function Documentation

void socketcan_bridge::SocketCANToTopic::frameCallback ( const can::Frame f)
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.

void socketcan_bridge::SocketCANToTopic::stateCallback ( const can::State s)
private

Definition at line 114 of file socketcan_to_topic.cpp.

Member Data Documentation

ros::Publisher socketcan_bridge::SocketCANToTopic::can_topic_
private

Definition at line 48 of file socketcan_to_topic.h.

can::DriverInterfaceSharedPtr socketcan_bridge::SocketCANToTopic::driver_
private

Definition at line 49 of file socketcan_to_topic.h.

can::FrameListenerConstSharedPtr socketcan_bridge::SocketCANToTopic::frame_listener_
private

Definition at line 51 of file socketcan_to_topic.h.

can::StateListenerConstSharedPtr socketcan_bridge::SocketCANToTopic::state_listener_
private

Definition at line 52 of file socketcan_to_topic.h.


The documentation for this class was generated from the following files:


socketcan_bridge
Author(s): Ivor Wanders
autogenerated on Sat May 4 2019 02:40:49