#include <protobuf2ros_publisher.h>
Public Member Functions | |
Protobuf2RosPublisher (ros::NodeHandle &nh, const std::string &topic, const std::string &pbMsgType, const std::string &frame_id_prefix) | |
virtual void | publish (std::shared_ptr<::google::protobuf::Message > pbMsg) |
virtual bool | used () |
Protected Attributes | |
const std::string | _tfPrefix |
ros::Publisher | pub |
Private Member Functions | |
Protobuf2RosPublisher & | operator= (const Protobuf2RosPublisher &) |
Generic implementation for publishing protobuf messages to ros
Definition at line 50 of file protobuf2ros_publisher.h.
rc::Protobuf2RosPublisher::Protobuf2RosPublisher | ( | ros::NodeHandle & | nh, |
const std::string & | topic, | ||
const std::string & | pbMsgType, | ||
const std::string & | frame_id_prefix | ||
) |
Internally creates a corresponding ros publisher
Definition at line 22 of file protobuf2ros_publisher.cc.
Protobuf2RosPublisher& rc::Protobuf2RosPublisher::operator= | ( | const Protobuf2RosPublisher & | ) | [private] |
void rc::Protobuf2RosPublisher::publish | ( | std::shared_ptr<::google::protobuf::Message > | pbMsg | ) | [virtual] |
Publish the generic protobuf message as a corresponding Ros Message
Definition at line 49 of file protobuf2ros_publisher.cc.
bool rc::Protobuf2RosPublisher::used | ( | ) | [virtual] |
Returns true if there are subscribers to the topic.
Definition at line 43 of file protobuf2ros_publisher.cc.
const std::string rc::Protobuf2RosPublisher::_tfPrefix [protected] |
Definition at line 75 of file protobuf2ros_publisher.h.
ros::Publisher rc::Protobuf2RosPublisher::pub [protected] |
Definition at line 74 of file protobuf2ros_publisher.h.