joint_state.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 #ifndef JOINT_STATES_CONVERTER_HPP
00019 #define JOINT_STATES_CONVERTER_HPP
00020 
00021 /*
00022 * LOCAL includes
00023 */
00024 #include "converter_base.hpp"
00025 #include "../tools/robot_description.hpp"
00026 #include <naoqi_driver/message_actions.h>
00027 
00028 /*
00029 * ROS includes
00030 */
00031 #include <urdf/model.h>
00032 #include <sensor_msgs/JointState.h>
00033 #include <robot_state_publisher/robot_state_publisher.h>
00034 
00035 namespace naoqi
00036 {
00037 namespace converter
00038 {
00039 
00040 class JointStateConverter : public BaseConverter<JointStateConverter>
00041 {
00042 
00043   typedef boost::function<void(sensor_msgs::JointState&, std::vector<geometry_msgs::TransformStamped>&) > Callback_t;
00044 
00045   typedef boost::shared_ptr<tf2_ros::Buffer> BufferPtr;
00046 
00047   typedef std::map<std::string, boost::shared_ptr<urdf::JointMimic> > MimicMap;
00048 
00049 public:
00050   JointStateConverter( const std::string& name, const float& frequency, const BufferPtr& tf2_buffer, const qi::SessionPtr& session );
00051 
00052   ~JointStateConverter();
00053 
00054   virtual void reset( );
00055 
00056   void registerCallback( const message_actions::MessageAction action, Callback_t cb );
00057 
00058   void callAll( const std::vector<message_actions::MessageAction>& actions );
00059 
00060 private:
00061 
00063   void addChildren(const KDL::SegmentMap::const_iterator segment);
00064   std::map<std::string, robot_state_publisher::SegmentPair> segments_, segments_fixed_;
00065   void setTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time, const std::string& tf_prefix);
00066   void setFixedTransforms(const std::string& tf_prefix, const ros::Time& time);
00067 
00069   BufferPtr tf2_buffer_;
00070 
00072   qi::AnyObject p_motion_;
00073 
00075   std::map<message_actions::MessageAction, Callback_t> callbacks_;
00076 
00078   std::string robot_desc_;
00079 
00081   MimicMap mimic_;
00082 
00084   sensor_msgs::JointState msg_joint_states_;
00085 
00087   std::vector<geometry_msgs::TransformStamped> tf_transforms_;
00088 
00089 }; // class
00090 
00091 } //publisher
00092 } // naoqi
00093 
00094 #endif


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sun Sep 17 2017 02:57:14