GlobalRecorder concept interface.
More...
#include <globalrecorder.hpp>
|
| GlobalRecorder (const std::string &prefix_topic) |
| Constructor for recorder interface. More...
|
|
void | startRecord (const std::string &prefix_bag="") |
| Initialize the recording of the ROSbag. More...
|
|
std::string | stopRecord (const std::string &robot_ip="<ROBOT_IP>") |
| Terminate the recording of the ROSbag. More...
|
|
template<class T > |
void | write (const std::string &topic, const T &msg, const ros::Time &time=ros::Time::now()) |
| Insert data into the ROSbag. More...
|
|
void | write (const std::string &topic, const std::vector< geometry_msgs::TransformStamped > &msgtf) |
|
bool | isStarted () |
| Check if the ROSbag is opened. More...
|
|
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
naoqi::recorder::GlobalRecorder::GlobalRecorder |
( |
const std::string & |
prefix_topic | ) |
|
Constructor for recorder interface.
bool naoqi::recorder::GlobalRecorder::isStarted |
( |
| ) |
|
Check if the ROSbag is opened.
void naoqi::recorder::GlobalRecorder::startRecord |
( |
const std::string & |
prefix_bag = "" | ) |
|
Initialize the recording of the ROSbag.
std::string naoqi::recorder::GlobalRecorder::stopRecord |
( |
const std::string & |
robot_ip = "<ROBOT_IP>" | ) |
|
Terminate the recording of the ROSbag.
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.
void naoqi::recorder::GlobalRecorder::write |
( |
const std::string & |
topic, |
|
|
const std::vector< geometry_msgs::TransformStamped > & |
msgtf |
|
) |
| |
rosbag::Bag naoqi::recorder::GlobalRecorder::_bag |
|
private |
bool naoqi::recorder::GlobalRecorder::_isStarted |
|
private |
std::string naoqi::recorder::GlobalRecorder::_nameBag |
|
private |
std::string naoqi::recorder::GlobalRecorder::_prefix_topic |
|
private |
boost::mutex naoqi::recorder::GlobalRecorder::_processMutex |
|
private |
std::vector<Topics> naoqi::recorder::GlobalRecorder::_topics |
|
private |
The documentation for this class was generated from the following files:
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/include/naoqi_driver/recorder/globalrecorder.hpp
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/src/recorder/globalrecorder.cpp