Public Member Functions | Private Attributes
naoqi::recorder::GlobalRecorder Class Reference

GlobalRecorder concept interface. More...

#include <globalrecorder.hpp>

List of all members.

Public Member Functions

 GlobalRecorder (const std::string &prefix_topic)
 Constructor for recorder interface.
bool isStarted ()
 Check if the ROSbag is opened.
void startRecord (const std::string &prefix_bag="")
 Initialize the recording of the ROSbag.
std::string stopRecord (const std::string &robot_ip="<ROBOT_IP>")
 Terminate the recording of the ROSbag.
template<class T >
void write (const std::string &topic, const T &msg, const ros::Time &time=ros::Time::now())
 Insert data into the ROSbag.
void write (const std::string &topic, const std::vector< geometry_msgs::TransformStamped > &msgtf)

Private Attributes

rosbag::Bag _bag
bool _isStarted
std::string _nameBag
std::string _prefix_topic
boost::mutex _processMutex
std::vector< Topics_topics

Detailed Description

GlobalRecorder concept interface.

Note:
this defines an private concept struct, which each instance has to implement
a type erasure pattern in implemented here to avoid strict inheritance, thus each possible publisher instance has to implement the virtual functions mentioned in the concept

Definition at line 57 of file globalrecorder.hpp.


Constructor & Destructor Documentation

naoqi::recorder::GlobalRecorder::GlobalRecorder ( const std::string &  prefix_topic)

Constructor for recorder interface.

Definition at line 58 of file globalrecorder.cpp.


Member Function Documentation

Check if the ROSbag is opened.

Definition at line 138 of file globalrecorder.cpp.

void naoqi::recorder::GlobalRecorder::startRecord ( const std::string &  prefix_bag = "")

Initialize the recording of the ROSbag.

Definition at line 74 of file globalrecorder.cpp.

std::string naoqi::recorder::GlobalRecorder::stopRecord ( const std::string &  robot_ip = "<ROBOT_IP>")

Terminate the recording of the ROSbag.

Definition at line 109 of file globalrecorder.cpp.

template<class T >
void naoqi::recorder::GlobalRecorder::write ( const std::string &  topic,
const T msg,
const ros::Time time = ros::Time::now() 
) [inline]

Insert data into the ROSbag.

Definition at line 81 of file globalrecorder.hpp.

void naoqi::recorder::GlobalRecorder::write ( const std::string &  topic,
const std::vector< geometry_msgs::TransformStamped > &  msgtf 
)

Definition at line 142 of file globalrecorder.cpp.


Member Data Documentation

Definition at line 108 of file globalrecorder.hpp.

Definition at line 110 of file globalrecorder.hpp.

Definition at line 109 of file globalrecorder.hpp.

Definition at line 106 of file globalrecorder.hpp.

Definition at line 107 of file globalrecorder.hpp.

Definition at line 113 of file globalrecorder.hpp.


The documentation for this class was generated from the following files:


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