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_STATE_RECORDER_HPP
00019 #define JOINT_STATE_RECORDER_HPP
00020 
00021 /*
00022 * BOOST includes
00023 */
00024 #include <boost/circular_buffer.hpp>
00025 
00026 /*
00027 * LOCAL includes
00028 */
00029 #include <naoqi_driver/recorder/globalrecorder.hpp>
00030 #include "../helpers/recorder_helpers.hpp"
00031 
00032 /*
00033 * ROS includes
00034 */
00035 #include <sensor_msgs/JointState.h>
00036 
00037 namespace naoqi
00038 {
00039 namespace recorder
00040 {
00041 
00042 class JointStateRecorder
00043 {
00044 
00045 public:
00046   JointStateRecorder( const std::string& topic, float buffer_frequency = 0 );
00047 
00048   void write( const sensor_msgs::JointState& js_msg,
00049               const std::vector<geometry_msgs::TransformStamped>& tf_transforms );
00050 
00051   void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr, float conv_frequency );
00052 
00053   void bufferize( const sensor_msgs::JointState& js_msg,
00054                   const std::vector<geometry_msgs::TransformStamped>& tf_transforms );
00055 
00056   void writeDump(const ros::Time& time);
00057 
00058   void setBufferDuration(float duration);
00059 
00060   inline std::string topic() const
00061   {
00062     return topic_;
00063   }
00064 
00065   inline bool isInitialized() const
00066   {
00067     return is_initialized_;
00068   }
00069 
00070   inline void subscribe( bool state)
00071   {
00072     is_subscribed_ = state;
00073   }
00074 
00075   inline bool isSubscribed() const
00076   {
00077     return is_subscribed_;
00078   }
00079 
00080 protected:
00081   std::string topic_;
00082 
00083   boost::circular_buffer<sensor_msgs::JointState> bufferJoinState_;
00084   boost::circular_buffer< std::vector<geometry_msgs::TransformStamped> > bufferTF_;
00085   size_t buffer_size_;
00086   float buffer_duration_;
00087 
00088   boost::mutex mutex_;
00089 
00090   bool is_initialized_;
00091   bool is_subscribed_;
00092 
00093   boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr_;
00094 
00095   float buffer_frequency_;
00096   float conv_frequency_;
00097   int counter_;
00098   int max_counter_;
00099 
00100 }; // class
00101 
00102 } //publisher
00103 } // naoqi
00104 
00105 #endif


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