globalrecorder.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 GLOBALRECORDER_HPP
00019 #define GLOBALRECORDER_HPP
00020 
00021 /*
00022 * LOCAL includes
00023 */
00024 #include <naoqi_driver/tools.hpp>
00025 
00026 /*
00027 * STANDARD includes
00028 */
00029 #include <string>
00030 
00031 /*
00032 * BOOST includes
00033 */
00034 # include <boost/thread/mutex.hpp>
00035 
00036 /*
00037 * ROS includes
00038 */
00039 #include <ros/ros.h>
00040 #include <rosbag/bag.h>
00041 #include <geometry_msgs/TransformStamped.h>
00042 
00043 
00044 
00045 namespace naoqi
00046 {
00047 namespace recorder
00048 {
00049 
00057 class GlobalRecorder
00058 {
00059 
00060 public:
00061 
00065   GlobalRecorder(const std::string& prefix_topic);
00066 
00070   void startRecord(const std::string& prefix_bag = "");
00071 
00075   std::string stopRecord(const std::string& robot_ip = "<ROBOT_IP>");
00076 
00080   template <class T>
00081   void write(const std::string& topic, const T& msg, const ros::Time& time = ros::Time::now() ) {
00082     std::string ros_topic;
00083     if (topic[0]!='/')
00084     {
00085       ros_topic = _prefix_topic+topic;
00086     }
00087     else
00088     {
00089       ros_topic = topic;
00090     }
00091     ros::Time time_msg = time;
00092     boost::mutex::scoped_lock writeLock( _processMutex );
00093     if (_isStarted) {
00094       _bag.write(ros_topic, time_msg, msg);
00095     }
00096   }
00097 
00098   void write(const std::string& topic, const std::vector<geometry_msgs::TransformStamped>& msgtf);
00099 
00103   bool isStarted();
00104 
00105 private:
00106   std::string _prefix_topic;
00107   boost::mutex _processMutex;
00108   rosbag::Bag _bag;
00109   std::string _nameBag;
00110   bool _isStarted;
00111 
00112   // TOPICS
00113   std::vector<Topics> _topics;
00114 
00115 }; // class globalrecorder
00116 } // recorder
00117 } //naoqi
00118 
00119 #endif


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