#include <moveto.hpp>
Public Member Functions | |
void | callback (const geometry_msgs::PoseStampedConstPtr &pose_msg) |
MovetoSubscriber (const std::string &name, const std::string &topic, const qi::SessionPtr &session, const boost::shared_ptr< tf2_ros::Buffer > &tf2_buffer) | |
void | reset (ros::NodeHandle &nh) |
~MovetoSubscriber () | |
Public Member Functions inherited from naoqi::subscriber::BaseSubscriber< MovetoSubscriber > | |
BaseSubscriber (const std::string &name, const std::string &topic, qi::SessionPtr session) | |
bool | isInitialized () const |
std::string | name () const |
std::string | topic () const |
virtual | ~BaseSubscriber () |
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 > | |
bool | is_initialized_ |
std::string | name_ |
const robot::Robot & | robot_ |
qi::SessionPtr | session_ |
std::string | topic_ |
Definition at line 39 of file moveto.hpp.
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 | ||
) |
Definition at line 36 of file moveto.cpp.
|
inline |
Definition at line 43 of file moveto.hpp.
void naoqi::subscriber::MovetoSubscriber::callback | ( | const geometry_msgs::PoseStampedConstPtr & | pose_msg | ) |
Definition at line 49 of file moveto.cpp.
void naoqi::subscriber::MovetoSubscriber::reset | ( | ros::NodeHandle & | nh | ) |
Definition at line 43 of file moveto.cpp.
|
private |
Definition at line 49 of file moveto.hpp.
|
private |
Definition at line 50 of file moveto.hpp.
|
private |
Definition at line 51 of file moveto.hpp.