#include <info.hpp>

| Public Member Functions | |
| InfoPublisher (const std::string &topic, const robot::Robot &robot_type) | |
| virtual bool | isSubscribed () const | 
| void | reset (ros::NodeHandle &nh) | 
|  Public Member Functions inherited from naoqi::publisher::BasicPublisher< naoqi_bridge_msgs::StringStamped > | |
| BasicPublisher (const std::string &topic) | |
| bool | isInitialized () const | 
| virtual void | publish (const naoqi_bridge_msgs::StringStamped &msg) | 
| std::string | topic () const | 
| virtual | ~BasicPublisher () | 
| Protected Attributes | |
| const robot::Robot & | robot_ | 
|  Protected Attributes inherited from naoqi::publisher::BasicPublisher< naoqi_bridge_msgs::StringStamped > | |
| bool | is_initialized_ | 
| ros::Publisher | pub_ | 
| std::string | topic_ | 
Definition at line 38 of file publishers/info.hpp.
| naoqi::publisher::InfoPublisher::InfoPublisher | ( | const std::string & | topic, | 
| const robot::Robot & | robot_type | ||
| ) | 
Definition at line 29 of file publishers/info.cpp.
| 
 | inlinevirtual | 
Reimplemented from naoqi::publisher::BasicPublisher< naoqi_bridge_msgs::StringStamped >.
Definition at line 45 of file publishers/info.hpp.
| 
 | virtual | 
Reimplemented from naoqi::publisher::BasicPublisher< naoqi_bridge_msgs::StringStamped >.
Definition at line 35 of file publishers/info.cpp.
| 
 | protected | 
Definition at line 51 of file publishers/info.hpp.