#include <robot_config.hpp>
Public Member Functions | |
| bool | callback (naoqi_bridge_msgs::GetRobotInfoRequest &req, naoqi_bridge_msgs::GetRobotInfoResponse &resp) |
| std::string | name () const |
| void | reset (ros::NodeHandle &nh) |
| RobotConfigService (const std::string &name, const std::string &topic, const qi::SessionPtr &session) | |
| std::string | topic () const |
| ~RobotConfigService () | |
Private Attributes | |
| const std::string | name_ |
| ros::ServiceServer | service_ |
| const qi::SessionPtr & | session_ |
| const std::string | topic_ |
Definition at line 35 of file robot_config.hpp.
| naoqi::service::RobotConfigService::RobotConfigService | ( | const std::string & | name, |
| const std::string & | topic, | ||
| const qi::SessionPtr & | session | ||
| ) |
Definition at line 26 of file robot_config.cpp.
Definition at line 40 of file robot_config.hpp.
| bool naoqi::service::RobotConfigService::callback | ( | naoqi_bridge_msgs::GetRobotInfoRequest & | req, |
| naoqi_bridge_msgs::GetRobotInfoResponse & | resp | ||
| ) |
Definition at line 37 of file robot_config.cpp.
| std::string naoqi::service::RobotConfigService::name | ( | ) | const [inline] |
Definition at line 42 of file robot_config.hpp.
| void naoqi::service::RobotConfigService::reset | ( | ros::NodeHandle & | nh | ) |
Definition at line 32 of file robot_config.cpp.
| std::string naoqi::service::RobotConfigService::topic | ( | ) | const [inline] |
Definition at line 47 of file robot_config.hpp.
const std::string naoqi::service::RobotConfigService::name_ [private] |
Definition at line 58 of file robot_config.hpp.
Definition at line 62 of file robot_config.hpp.
const qi::SessionPtr& naoqi::service::RobotConfigService::session_ [private] |
Definition at line 61 of file robot_config.hpp.
const std::string naoqi::service::RobotConfigService::topic_ [private] |
Definition at line 59 of file robot_config.hpp.