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 <tf2_ros/buffer.h>
00034 #include <robot_state_publisher/robot_state_publisher.h>
00035 
00036 namespace naoqi
00037 {
00038 namespace converter
00039 {
00040 
00041 class JointStateConverter : public BaseConverter<JointStateConverter>
00042 {
00043 
00044   typedef boost::function<void(sensor_msgs::JointState&, std::vector<geometry_msgs::TransformStamped>&) > Callback_t;
00045 
00046   typedef boost::shared_ptr<tf2_ros::Buffer> BufferPtr;
00047 
00048   typedef std::map<std::string, boost::shared_ptr<urdf::JointMimic> > MimicMap;
00049 
00050 public:
00051   JointStateConverter( const std::string& name, const float& frequency, const BufferPtr& tf2_buffer, const qi::SessionPtr& session );
00052 
00053   ~JointStateConverter();
00054 
00055   virtual void reset( );
00056 
00057   void registerCallback( const message_actions::MessageAction action, Callback_t cb );
00058 
00059   void callAll( const std::vector<message_actions::MessageAction>& actions );
00060 
00061 private:
00062 
00064   void addChildren(const KDL::SegmentMap::const_iterator segment);
00065   std::map<std::string, robot_state_publisher::SegmentPair> segments_, segments_fixed_;
00066   void setTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time, const std::string& tf_prefix);
00067   void setFixedTransforms(const std::string& tf_prefix, const ros::Time& time);
00068 
00070   BufferPtr tf2_buffer_;
00071 
00073   qi::AnyObject p_motion_;
00074 
00076   std::map<message_actions::MessageAction, Callback_t> callbacks_;
00077 
00079   std::string robot_desc_;
00080 
00082   MimicMap mimic_;
00083 
00085   sensor_msgs::JointState msg_joint_states_;
00086 
00088   std::vector<geometry_msgs::TransformStamped> tf_transforms_;
00089 
00090 }; // class
00091 
00092 } //publisher
00093 } // naoqi
00094 
00095 #endif


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56