#include <topic_handlers.h>
Public Member Functions | |
std::string | get_topic () |
Subscriber (ros::NodeHandle &nh, rosserial_msgs::TopicInfo &topic_info, boost::function< void(std::vector< uint8_t > &buffer)> write_fn) | |
Private Member Functions | |
void | handle (const boost::shared_ptr< topic_tools::ShapeShifter const > &msg) |
Private Attributes | |
ros::Subscriber | subscriber_ |
boost::function< void(std::vector < uint8_t > &buffer)> | write_fn_ |
Definition at line 93 of file topic_handlers.h.
rosserial_server::Subscriber::Subscriber | ( | ros::NodeHandle & | nh, |
rosserial_msgs::TopicInfo & | topic_info, | ||
boost::function< void(std::vector< uint8_t > &buffer)> | write_fn | ||
) | [inline] |
Definition at line 95 of file topic_handlers.h.
std::string rosserial_server::Subscriber::get_topic | ( | ) | [inline] |
Definition at line 106 of file topic_handlers.h.
void rosserial_server::Subscriber::handle | ( | const boost::shared_ptr< topic_tools::ShapeShifter const > & | msg | ) | [inline, private] |
Definition at line 111 of file topic_handlers.h.
Definition at line 121 of file topic_handlers.h.
boost::function<void(std::vector<uint8_t>& buffer)> rosserial_server::Subscriber::write_fn_ [private] |
Definition at line 122 of file topic_handlers.h.