teleop.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Aldebaran
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016  */
00017 
00018 
00019 #ifndef TELEOP_SUBSCRIBER_HPP
00020 #define TELEOP_SUBSCRIBER_HPP
00021 
00022 /*
00023  * LOCAL includes
00024  */
00025 #include "subscriber_base.hpp"
00026 
00027 /*
00028  * ROS includes
00029  */
00030 #include <ros/ros.h>
00031 #include <geometry_msgs/Twist.h>
00032 #include <naoqi_bridge_msgs/JointAnglesWithSpeed.h>
00033 
00034 namespace naoqi
00035 {
00036 namespace subscriber
00037 {
00038 
00039 class TeleopSubscriber: public BaseSubscriber<TeleopSubscriber>
00040 {
00041 public:
00042   TeleopSubscriber( const std::string& name, const std::string& cmd_vel_topic, const std::string& joint_angles_topic, const qi::SessionPtr& session );
00043   ~TeleopSubscriber(){}
00044 
00045   void reset( ros::NodeHandle& nh );
00046   void cmd_vel_callback( const geometry_msgs::TwistConstPtr& twist_msg );
00047   void joint_angles_callback( const naoqi_bridge_msgs::JointAnglesWithSpeedConstPtr& js_msg );
00048 
00049 private:
00050 
00051   std::string cmd_vel_topic_;
00052   std::string joint_angles_topic_;
00053 
00054   qi::AnyObject p_motion_;
00055   ros::Subscriber sub_cmd_vel_;
00056   ros::Subscriber sub_joint_angles_;
00057 
00058 
00059 
00060 }; // class Teleop
00061 
00062 } // subscriber
00063 }// naoqi
00064 #endif


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56