naoqidriver
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_CONVERTER_HPP
19 #define JOINT_STATES_CONVERTER_HPP
20 
21 /*
22 * LOCAL includes
23 */
24 #include "converter_base.hpp"
25 #include "../tools/robot_description.hpp"
27 
28 /*
29 * ROS includes
30 */
31 #include <sensor_msgs/JointState.h>
32 #include <robot_state_publisher/robot_state_publisher.h>
33 
34 namespace naoqi
35 {
36 namespace converter
37 {
38 
39 class JointStateConverter : public BaseConverter<JointStateConverter>
40 {
41 
42  typedef boost::function<void(sensor_msgs::JointState&, std::vector<geometry_msgs::TransformStamped>&) > Callback_t;
43 
44  typedef boost::shared_ptr<tf2_ros::Buffer> BufferPtr;
45 
46 public:
47  JointStateConverter( const std::string& name, const float& frequency, const BufferPtr& tf2_buffer, const qi::SessionPtr& session );
48 
50 
51  virtual void reset( );
52 
54 
55  void callAll( const std::vector<message_actions::MessageAction>& actions );
56 
57 private:
58 
60  void addChildren(const KDL::SegmentMap::const_iterator segment);
61  std::map<std::string, robot_state_publisher::SegmentPair> segments_, segments_fixed_;
62  void setTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time, const std::string& tf_prefix);
63  void setFixedTransforms(const std::string& tf_prefix, const ros::Time& time);
64 
66  BufferPtr tf2_buffer_;
67 
69  qi::AnyObject p_motion_;
70 
72  std::map<message_actions::MessageAction, Callback_t> callbacks_;
73 
75  std::string robot_desc_;
76 
78  sensor_msgs::JointState msg_joint_states_;
79 
81  std::vector<geometry_msgs::TransformStamped> tf_transforms_;
82 
83 }; // class
84 
85 } //publisher
86 } // naoqi
87 
88 #endif
std::string name() const
Definition: converter_base.hpp:54
float frequency() const
Definition: converter_base.hpp:59
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
Definition: joint_state.cpp:71
MessageAction
Definition: message_actions.h:9
BufferPtr tf2_buffer_
Definition: joint_state.hpp:66
boost::function< void(sensor_msgs::JointState &, std::vector< geometry_msgs::TransformStamped > &) > Callback_t
Definition: joint_state.hpp:42
Definition: audio.cpp:29
~JointStateConverter()
Definition: joint_state.cpp:50
qi::AnyObject p_motion_
Definition: joint_state.hpp:69
virtual void reset()
Definition: joint_state.cpp:55
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: joint_state.hpp:72
Definition: converter_base.hpp:40
void setFixedTransforms(const std::string &tf_prefix, const ros::Time &time)
Definition: joint_state.cpp:199
std::map< std::string, robot_state_publisher::SegmentPair > segments_
Definition: joint_state.hpp:61
void addChildren(const KDL::SegmentMap::const_iterator segment)
Definition: joint_state.cpp:227
sensor_msgs::JointState msg_joint_states_
Definition: joint_state.hpp:78
std::string robot_desc_
Definition: joint_state.hpp:75
boost::shared_ptr< tf2_ros::Buffer > BufferPtr
Definition: joint_state.hpp:44
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: joint_state.cpp:76
std::map< std::string, robot_state_publisher::SegmentPair > segments_fixed_
Definition: joint_state.hpp:61
Definition: joint_state.hpp:39
void setTransforms(const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix)
Definition: joint_state.cpp:167
std::vector< geometry_msgs::TransformStamped > tf_transforms_
Definition: joint_state.hpp:81
JointStateConverter(const std::string &name, const float &frequency, const BufferPtr &tf2_buffer, const qi::SessionPtr &session)
Definition: joint_state.cpp:42