#include <recorder.h>
|
template<class T > |
static std::string | timeToStr (T ros_t) |
|
Definition at line 120 of file recorder.h.
◆ Recorder()
◆ checkDisk()
bool rosbag::Recorder::checkDisk |
( |
| ) |
|
|
private |
◆ checkDuration()
bool rosbag::Recorder::checkDuration |
( |
const ros::Time & |
t | ) |
|
|
private |
◆ checkLogging()
bool rosbag::Recorder::checkLogging |
( |
| ) |
|
|
private |
◆ checkNumSplits()
void rosbag::Recorder::checkNumSplits |
( |
| ) |
|
|
private |
◆ checkSize()
bool rosbag::Recorder::checkSize |
( |
| ) |
|
|
private |
◆ doCheckMaster()
◆ doQueue()
Callback to be invoked to save messages into a queue.
Definition at line 327 of file recorder.cpp.
◆ doRecord()
void rosbag::Recorder::doRecord |
( |
| ) |
|
|
private |
Thread that actually does writing to file.
Definition at line 517 of file recorder.cpp.
◆ doRecordSnapshotter()
void rosbag::Recorder::doRecordSnapshotter |
( |
| ) |
|
|
private |
◆ doTrigger()
void rosbag::Recorder::doTrigger |
( |
| ) |
|
◆ isSubscribed()
bool rosbag::Recorder::isSubscribed |
( |
std::string const & |
topic | ) |
const |
◆ printUsage()
void rosbag::Recorder::printUsage |
( |
| ) |
|
|
private |
◆ run()
int rosbag::Recorder::run |
( |
| ) |
|
◆ scheduledCheckDisk()
bool rosbag::Recorder::scheduledCheckDisk |
( |
| ) |
|
|
private |
◆ shouldSubscribeToTopic()
bool rosbag::Recorder::shouldSubscribeToTopic |
( |
std::string const & |
topic, |
|
|
bool |
from_node = false |
|
) |
| |
|
private |
◆ snapshotTrigger()
void rosbag::Recorder::snapshotTrigger |
( |
std_msgs::Empty::ConstPtr |
trigger | ) |
|
|
private |
Callback to be invoked to actually do the recording.
Definition at line 407 of file recorder.cpp.
◆ startWriting()
void rosbag::Recorder::startWriting |
( |
| ) |
|
|
private |
◆ stopWriting()
void rosbag::Recorder::stopWriting |
( |
| ) |
|
|
private |
◆ subscribe()
◆ timeToStr()
template<class T >
std::string rosbag::Recorder::timeToStr |
( |
T |
ros_t | ) |
|
|
staticprivate |
◆ updateFilenames()
void rosbag::Recorder::updateFilenames |
( |
| ) |
|
|
private |
◆ bag_
Bag rosbag::Recorder::bag_ |
|
private |
◆ check_disk_mutex_
boost::mutex rosbag::Recorder::check_disk_mutex_ |
|
private |
◆ check_disk_next_
◆ current_files_
std::list<std::string> rosbag::Recorder::current_files_ |
|
private |
◆ currently_recording_
std::set<std::string> rosbag::Recorder::currently_recording_ |
|
private |
set of currently recording topics
Definition at line 168 of file recorder.h.
◆ exit_code_
int rosbag::Recorder::exit_code_ |
|
private |
◆ last_buffer_warn_
ros::Time rosbag::Recorder::last_buffer_warn_ |
|
private |
◆ max_queue_size_
uint64_t rosbag::Recorder::max_queue_size_ |
|
private |
◆ num_subscribers_
int rosbag::Recorder::num_subscribers_ |
|
private |
used for book-keeping of our number of subscribers
Definition at line 169 of file recorder.h.
◆ options_
◆ pub_begin_write
◆ queue_
◆ queue_condition_
boost::condition_variable_any rosbag::Recorder::queue_condition_ |
|
private |
conditional variable for queue
Definition at line 173 of file recorder.h.
◆ queue_mutex_
boost::mutex rosbag::Recorder::queue_mutex_ |
|
private |
◆ queue_queue_
queue of queues to be used by the snapshot recorders
Definition at line 181 of file recorder.h.
◆ queue_size_
uint64_t rosbag::Recorder::queue_size_ |
|
private |
◆ split_count_
uint64_t rosbag::Recorder::split_count_ |
|
private |
◆ start_time_
◆ target_filename_
std::string rosbag::Recorder::target_filename_ |
|
private |
◆ warn_next_
◆ write_filename_
std::string rosbag::Recorder::write_filename_ |
|
private |
◆ writing_enabled_
bool rosbag::Recorder::writing_enabled_ |
|
private |
The documentation for this class was generated from the following files:
rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:34:21