src
subscribers
teleop.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 TELEOP_SUBSCRIBER_HPP
20
#define TELEOP_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/Twist.h>
32
#include <naoqi_bridge_msgs/JointAnglesWithSpeed.h>
33
34
namespace
naoqi
35
{
36
namespace
subscriber
37
{
38
39
class
TeleopSubscriber
:
public
BaseSubscriber
<TeleopSubscriber>
40
{
41
public
:
42
TeleopSubscriber
(
const
std::string&
name
,
const
std::string& cmd_vel_topic,
const
std::string& joint_angles_topic,
const
qi::SessionPtr&
session
);
43
~TeleopSubscriber
(){}
44
45
void
reset
(
ros::NodeHandle
& nh );
46
void
cmd_vel_callback
(
const
geometry_msgs::TwistConstPtr& twist_msg );
47
void
joint_angles_callback
(
const
naoqi_bridge_msgs::JointAnglesWithSpeedConstPtr& js_msg );
48
49
private
:
50
51
std::string
cmd_vel_topic_
;
52
std::string
joint_angles_topic_
;
53
54
qi::AnyObject
p_motion_
;
55
ros::Subscriber
sub_cmd_vel_
;
56
ros::Subscriber
sub_joint_angles_
;
57
58
59
60
};
// class Teleop
61
62
}
// subscriber
63
}
// naoqi
64
#endif
naoqi::subscriber::TeleopSubscriber::~TeleopSubscriber
~TeleopSubscriber()
Definition:
teleop.hpp:43
naoqi::subscriber::BaseSubscriber
Definition:
subscriber_base.hpp:39
naoqi::subscriber::BaseSubscriber< TeleopSubscriber >::name
std::string name() const
Definition:
subscriber_base.hpp:53
naoqi::subscriber::TeleopSubscriber::p_motion_
qi::AnyObject p_motion_
Definition:
teleop.hpp:54
naoqi::subscriber::TeleopSubscriber::joint_angles_topic_
std::string joint_angles_topic_
Definition:
teleop.hpp:52
ros.h
session
session
naoqi::subscriber::TeleopSubscriber::TeleopSubscriber
TeleopSubscriber(const std::string &name, const std::string &cmd_vel_topic, const std::string &joint_angles_topic, const qi::SessionPtr &session)
Definition:
teleop.cpp:29
naoqi::subscriber::TeleopSubscriber::sub_joint_angles_
ros::Subscriber sub_joint_angles_
Definition:
teleop.hpp:56
naoqi::subscriber::TeleopSubscriber::cmd_vel_topic_
std::string cmd_vel_topic_
Definition:
teleop.hpp:51
naoqi
Definition:
converter.hpp:29
naoqi::subscriber::TeleopSubscriber::sub_cmd_vel_
ros::Subscriber sub_cmd_vel_
Definition:
teleop.hpp:55
naoqi::subscriber::TeleopSubscriber::cmd_vel_callback
void cmd_vel_callback(const geometry_msgs::TwistConstPtr &twist_msg)
Definition:
teleop.cpp:44
subscriber_base.hpp
naoqi::subscriber::TeleopSubscriber::joint_angles_callback
void joint_angles_callback(const naoqi_bridge_msgs::JointAnglesWithSpeedConstPtr &js_msg)
Definition:
teleop.cpp:55
naoqi::subscriber::TeleopSubscriber::reset
void reset(ros::NodeHandle &nh)
Definition:
teleop.cpp:36
naoqi::subscriber::TeleopSubscriber
Definition:
teleop.hpp:39
ros::NodeHandle
ros::Subscriber
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06