converters/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 <urdf/model.h>
32 #include <sensor_msgs/JointState.h>
33 #include <tf2_ros/buffer.h>
35 
36 namespace naoqi
37 {
38 namespace converter
39 {
40 
41 class JointStateConverter : public BaseConverter<JointStateConverter>
42 {
43 
44  typedef boost::function<void(sensor_msgs::JointState&, std::vector<geometry_msgs::TransformStamped>&) > Callback_t;
45 
47 
48  typedef std::map<std::string, urdf::JointMimicSharedPtr> MimicMap;
49 
50 public:
51  JointStateConverter( const std::string& name, const float& frequency, const BufferPtr& tf2_buffer, const qi::SessionPtr& session );
52 
54 
55  virtual void reset( );
56 
58 
59  void callAll( const std::vector<message_actions::MessageAction>& actions );
60 
61 private:
62 
64  void addChildren(const KDL::SegmentMap::const_iterator segment);
65  std::map<std::string, robot_state_publisher::SegmentPair> segments_, segments_fixed_;
66  void setTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time, const std::string& tf_prefix);
67  void setFixedTransforms(const std::string& tf_prefix, const ros::Time& time);
68 
70  BufferPtr tf2_buffer_;
71 
73  qi::AnyObject p_motion_;
74  qi::AnyObject p_memory_;
75 
77  std::map<message_actions::MessageAction, Callback_t> callbacks_;
78 
80  std::string robot_desc_;
81 
83  MimicMap mimic_;
84 
86  sensor_msgs::JointState msg_joint_states_;
87 
89  std::vector<geometry_msgs::TransformStamped> tf_transforms_;
90 
91 }; // class
92 
93 } //publisher
94 } // naoqi
95 
96 #endif
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
std::map< std::string, urdf::JointMimicSharedPtr > MimicMap
boost::function< void(sensor_msgs::JointState &, std::vector< geometry_msgs::TransformStamped > &) > Callback_t
std::map< message_actions::MessageAction, Callback_t > callbacks_
void setFixedTransforms(const std::string &tf_prefix, const ros::Time &time)
std::map< std::string, robot_state_publisher::SegmentPair > segments_
void addChildren(const KDL::SegmentMap::const_iterator segment)
boost::shared_ptr< tf2_ros::Buffer > BufferPtr
void callAll(const std::vector< message_actions::MessageAction > &actions)
std::map< std::string, robot_state_publisher::SegmentPair > segments_fixed_
void setTransforms(const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix)
std::vector< geometry_msgs::TransformStamped > tf_transforms_
JointStateConverter(const std::string &name, const float &frequency, const BufferPtr &tf2_buffer, const qi::SessionPtr &session)


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