naoqidriver
Public Member Functions | Private Attributes
naoqi::subscriber::MovetoSubscriber Class Reference

#include <moveto.hpp>

Inheritance diagram for naoqi::subscriber::MovetoSubscriber:
naoqi::subscriber::BaseSubscriber< MovetoSubscriber >

Public Member Functions

 MovetoSubscriber (const std::string &name, const std::string &topic, const qi::SessionPtr &session, const boost::shared_ptr< tf2_ros::Buffer > &tf2_buffer)
 
 ~MovetoSubscriber ()
 
void reset (ros::NodeHandle &nh)
 
void callback (const geometry_msgs::PoseStampedConstPtr &pose_msg)
 
- Public Member Functions inherited from naoqi::subscriber::BaseSubscriber< MovetoSubscriber >
 BaseSubscriber (const std::string &name, const std::string &topic, qi::SessionPtr session)
 
virtual ~BaseSubscriber ()
 
std::string name () const
 
std::string topic () const
 
bool isInitialized () const
 

Private Attributes

qi::AnyObject p_motion_
 
ros::Subscriber sub_moveto_
 
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
 

Additional Inherited Members

- Protected Attributes inherited from naoqi::subscriber::BaseSubscriber< MovetoSubscriber >
std::string name_
 
std::string topic_
 
bool is_initialized_
 
const robot::Robotrobot_
 
qi::SessionPtr session_
 

Constructor & Destructor Documentation

naoqi::subscriber::MovetoSubscriber::MovetoSubscriber ( const std::string &  name,
const std::string &  topic,
const qi::SessionPtr &  session,
const boost::shared_ptr< tf2_ros::Buffer > &  tf2_buffer 
)
naoqi::subscriber::MovetoSubscriber::~MovetoSubscriber ( )
inline

Member Function Documentation

void naoqi::subscriber::MovetoSubscriber::callback ( const geometry_msgs::PoseStampedConstPtr &  pose_msg)
void naoqi::subscriber::MovetoSubscriber::reset ( ros::NodeHandle &  nh)

Field Documentation

qi::AnyObject naoqi::subscriber::MovetoSubscriber::p_motion_
private
ros::Subscriber naoqi::subscriber::MovetoSubscriber::sub_moveto_
private
boost::shared_ptr<tf2_ros::Buffer> naoqi::subscriber::MovetoSubscriber::tf2_buffer_
private

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