moveto.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 
18 
19 #ifndef MOVETO_SUBSCRIBER_HPP
20 #define MOVETO_SUBSCRIBER_HPP
21 
22 /*
23  * LOCAL includes
24  */
25 #include "subscriber_base.hpp"
26 
27 /*
28  * ROS includes
29  */
30 #include <ros/ros.h>
31 #include <geometry_msgs/PoseStamped.h>
32 #include <tf2_ros/buffer.h>
33 
34 namespace naoqi
35 {
36 namespace subscriber
37 {
38 
39 class MovetoSubscriber: public BaseSubscriber<MovetoSubscriber>
40 {
41 public:
42  MovetoSubscriber( const std::string& name, const std::string& topic, const qi::SessionPtr& session, const boost::shared_ptr<tf2_ros::Buffer>& tf2_buffer );
44 
45  void reset( ros::NodeHandle& nh );
46  void callback( const geometry_msgs::PoseStampedConstPtr& pose_msg );
47 
48 private:
49  qi::AnyObject p_motion_;
52 }; // class Teleop
53 
54 } // subscriber
55 }// naoqi
56 #endif
void callback(const geometry_msgs::PoseStampedConstPtr &pose_msg)
Definition: moveto.cpp:49
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
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
Definition: moveto.hpp:51


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26