19 #ifndef MOVETO_SUBSCRIBER_HPP
20 #define MOVETO_SUBSCRIBER_HPP
31 #include <geometry_msgs/PoseStamped.h>
32 #include <tf2_ros/buffer.h>
42 MovetoSubscriber(
const std::string&
name,
const std::string&
topic,
const qi::SessionPtr& session,
const boost::shared_ptr<tf2_ros::Buffer>& tf2_buffer );
45 void reset( ros::NodeHandle& nh );
46 void callback(
const geometry_msgs::PoseStampedConstPtr& pose_msg );
ros::Subscriber sub_moveto_
Definition: moveto.hpp:50
Definition: moveto.hpp:39
void callback(const geometry_msgs::PoseStampedConstPtr &pose_msg)
Definition: moveto.cpp:49
std::string name() const
Definition: subscriber_base.hpp:53
void reset(ros::NodeHandle &nh)
Definition: moveto.cpp:43
MovetoSubscriber(const std::string &name, const std::string &topic, const qi::SessionPtr &session, const boost::shared_ptr< tf2_ros::Buffer > &tf2_buffer)
Definition: moveto.cpp:36
std::string topic() const
Definition: subscriber_base.hpp:58
Definition: subscriber_base.hpp:39
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
Definition: moveto.hpp:51
~MovetoSubscriber()
Definition: moveto.hpp:43
qi::AnyObject p_motion_
Definition: moveto.hpp:49