recorder/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_STATE_RECORDER_HPP
19 #define JOINT_STATE_RECORDER_HPP
20 
21 /*
22 * BOOST includes
23 */
24 #include <boost/circular_buffer.hpp>
25 
26 /*
27 * LOCAL includes
28 */
30 #include "../helpers/recorder_helpers.hpp"
31 
32 /*
33 * ROS includes
34 */
35 #include <sensor_msgs/JointState.h>
36 
37 namespace naoqi
38 {
39 namespace recorder
40 {
41 
43 {
44 
45 public:
46  JointStateRecorder( const std::string& topic, float buffer_frequency = 0 );
47 
48  void write( const sensor_msgs::JointState& js_msg,
49  const std::vector<geometry_msgs::TransformStamped>& tf_transforms );
50 
51  void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr, float conv_frequency );
52 
53  void bufferize( const sensor_msgs::JointState& js_msg,
54  const std::vector<geometry_msgs::TransformStamped>& tf_transforms );
55 
56  void writeDump(const ros::Time& time);
57 
58  void setBufferDuration(float duration);
59 
60  inline std::string topic() const
61  {
62  return topic_;
63  }
64 
65  inline bool isInitialized() const
66  {
67  return is_initialized_;
68  }
69 
70  inline void subscribe( bool state)
71  {
72  is_subscribed_ = state;
73  }
74 
75  inline bool isSubscribed() const
76  {
77  return is_subscribed_;
78  }
79 
80 protected:
81  std::string topic_;
82 
83  boost::circular_buffer<sensor_msgs::JointState> bufferJoinState_;
84  boost::circular_buffer< std::vector<geometry_msgs::TransformStamped> > bufferTF_;
85  size_t buffer_size_;
87 
88  boost::mutex mutex_;
89 
92 
94 
97  int counter_;
99 
100 }; // class
101 
102 } //publisher
103 } // naoqi
104 
105 #endif
void bufferize(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
boost::circular_buffer< sensor_msgs::JointState > bufferJoinState_
JointStateRecorder(const std::string &topic, float buffer_frequency=0)
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float conv_frequency)
boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr_
void write(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
void writeDump(const ros::Time &time)
boost::circular_buffer< std::vector< geometry_msgs::TransformStamped > > bufferTF_


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