src
publishers
publishers/joint_state.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
#ifndef JOINT_STATES_PUBLISHER_HPP
19
#define JOINT_STATES_PUBLISHER_HPP
20
21
/*
22
* ROS includes
23
*/
24
#include <
ros/ros.h
>
25
#include <geometry_msgs/Transform.h>
26
#include <sensor_msgs/JointState.h>
27
#include <
tf2_ros/transform_broadcaster.h
>
28
29
namespace
naoqi
30
{
31
namespace
publisher
32
{
33
34
class
JointStatePublisher
35
{
36
37
public
:
38
JointStatePublisher
(
const
std::string&
topic
=
"/joint_states"
);
39
40
inline
std::string
topic
()
const
41
{
42
return
topic_
;
43
}
44
45
inline
bool
isInitialized
()
const
46
{
47
return
is_initialized_
;
48
}
49
50
virtual
void
publish
(
const
sensor_msgs::JointState& js_msg,
51
const
std::vector<geometry_msgs::TransformStamped>& tf_transforms );
52
53
virtual
void
reset
(
ros::NodeHandle
& nh );
54
55
virtual
bool
isSubscribed
()
const
;
56
57
private
:
58
boost::shared_ptr<tf2_ros::TransformBroadcaster>
tf_broadcasterPtr_
;
59
61
ros::Publisher
pub_joint_states_
;
62
63
std::string
topic_
;
64
65
bool
is_initialized_
;
66
67
};
// class
68
69
}
//publisher
70
}
// naoqi
71
72
#endif
naoqi::publisher::JointStatePublisher::isInitialized
bool isInitialized() const
Definition:
publishers/joint_state.hpp:45
ros::Publisher
boost::shared_ptr< tf2_ros::TransformBroadcaster >
naoqi::publisher::JointStatePublisher::is_initialized_
bool is_initialized_
Definition:
publishers/joint_state.hpp:65
ros.h
naoqi::publisher::JointStatePublisher::tf_broadcasterPtr_
boost::shared_ptr< tf2_ros::TransformBroadcaster > tf_broadcasterPtr_
Definition:
publishers/joint_state.hpp:58
naoqi::publisher::JointStatePublisher::JointStatePublisher
JointStatePublisher(const std::string &topic="/joint_states")
Definition:
publishers/joint_state.cpp:28
transform_broadcaster.h
naoqi
Definition:
converter.hpp:29
naoqi::publisher::JointStatePublisher::isSubscribed
virtual bool isSubscribed() const
Definition:
publishers/joint_state.cpp:54
naoqi::publisher::JointStatePublisher::publish
virtual void publish(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
Definition:
publishers/joint_state.cpp:33
naoqi::publisher::JointStatePublisher::topic
std::string topic() const
Definition:
publishers/joint_state.hpp:40
naoqi::publisher::JointStatePublisher
Definition:
publishers/joint_state.hpp:34
naoqi::publisher::JointStatePublisher::reset
virtual void reset(ros::NodeHandle &nh)
Definition:
publishers/joint_state.cpp:45
naoqi::publisher::JointStatePublisher::topic_
std::string topic_
Definition:
publishers/joint_state.hpp:63
naoqi::publisher::JointStatePublisher::pub_joint_states_
ros::Publisher pub_joint_states_
Definition:
publishers/joint_state.hpp:61
ros::NodeHandle
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06