Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
rosbag::Recorder Class Reference

#include <recorder.h>

Public Member Functions

void doTrigger ()
 
bool isSubscribed (std::string const &topic) const
 
 Recorder (RecorderOptions const &options)
 
int run ()
 
boost::shared_ptr< ros::Subscribersubscribe (std::string const &topic)
 

Private Member Functions

bool checkDisk ()
 
bool checkDuration (const ros::Time &)
 
bool checkLogging ()
 
void checkNumSplits ()
 
bool checkSize ()
 
void doCheckMaster (ros::TimerEvent const &e, ros::NodeHandle &node_handle)
 
void doQueue (const ros::MessageEvent< topic_tools::ShapeShifter const > &msg_event, std::string const &topic, boost::shared_ptr< ros::Subscriber > subscriber, boost::shared_ptr< int > count)
 Callback to be invoked to save messages into a queue. More...
 
void doRecord ()
 Thread that actually does writing to file. More...
 
void doRecordSnapshotter ()
 
void printUsage ()
 
bool scheduledCheckDisk ()
 
bool shouldSubscribeToTopic (std::string const &topic, bool from_node=false)
 
void snapshotTrigger (std_msgs::Empty::ConstPtr trigger)
 Callback to be invoked to actually do the recording. More...
 
void startWriting ()
 
void stopWriting ()
 
void updateFilenames ()
 

Static Private Member Functions

template<class T >
static std::string timeToStr (T ros_t)
 

Private Attributes

Bag bag_
 
boost::mutex check_disk_mutex_
 
ros::WallTime check_disk_next_
 
std::list< std::string > current_files_
 
std::set< std::string > currently_recording_
 set of currently recording topics More...
 
int exit_code_
 eventual exit code More...
 
ros::Time last_buffer_warn_
 
uint64_t max_queue_size_
 max queue size More...
 
int num_subscribers_
 used for book-keeping of our number of subscribers More...
 
RecorderOptions options_
 
ros::Publisher pub_begin_write
 
std::queue< OutgoingMessage > * queue_
 queue for storing More...
 
boost::condition_variable_any queue_condition_
 conditional variable for queue More...
 
boost::mutex queue_mutex_
 mutex for queue More...
 
std::queue< OutgoingQueuequeue_queue_
 queue of queues to be used by the snapshot recorders More...
 
uint64_t queue_size_
 queue size More...
 
uint64_t split_count_
 split count More...
 
ros::Time start_time_
 
std::string target_filename_
 
ros::WallTime warn_next_
 
std::string write_filename_
 
bool writing_enabled_
 

Detailed Description

Definition at line 120 of file recorder.h.

Constructor & Destructor Documentation

◆ Recorder()

rosbag::Recorder::Recorder ( RecorderOptions const &  options)

Definition at line 119 of file recorder.cpp.

Member Function Documentation

◆ checkDisk()

bool rosbag::Recorder::checkDisk ( )
private

Definition at line 705 of file recorder.cpp.

◆ checkDuration()

bool rosbag::Recorder::checkDuration ( const ros::Time t)
private

Definition at line 490 of file recorder.cpp.

◆ checkLogging()

bool rosbag::Recorder::checkLogging ( )
private

Definition at line 761 of file recorder.cpp.

◆ checkNumSplits()

void rosbag::Recorder::checkNumSplits ( )
private

Definition at line 452 of file recorder.cpp.

◆ checkSize()

bool rosbag::Recorder::checkSize ( )
private

Definition at line 469 of file recorder.cpp.

◆ doCheckMaster()

void rosbag::Recorder::doCheckMaster ( ros::TimerEvent const &  e,
ros::NodeHandle node_handle 
)
private

Definition at line 635 of file recorder.cpp.

◆ doQueue()

void rosbag::Recorder::doQueue ( const ros::MessageEvent< topic_tools::ShapeShifter const > &  msg_event,
std::string const &  topic,
boost::shared_ptr< ros::Subscriber subscriber,
boost::shared_ptr< int >  count 
)
private

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

Definition at line 597 of file recorder.cpp.

◆ doTrigger()

void rosbag::Recorder::doTrigger ( )

Definition at line 686 of file recorder.cpp.

◆ isSubscribed()

bool rosbag::Recorder::isSubscribed ( std::string const &  topic) const

Definition at line 278 of file recorder.cpp.

◆ printUsage()

void rosbag::Recorder::printUsage ( )
private

◆ run()

int rosbag::Recorder::run ( )

Definition at line 129 of file recorder.cpp.

◆ scheduledCheckDisk()

bool rosbag::Recorder::scheduledCheckDisk ( )
private

Definition at line 695 of file recorder.cpp.

◆ shouldSubscribeToTopic()

bool rosbag::Recorder::shouldSubscribeToTopic ( std::string const &  topic,
bool  from_node = false 
)
private

Definition at line 282 of file recorder.cpp.

◆ 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

Definition at line 423 of file recorder.cpp.

◆ stopWriting()

void rosbag::Recorder::stopWriting ( )
private

Definition at line 446 of file recorder.cpp.

◆ subscribe()

shared_ptr< ros::Subscriber > rosbag::Recorder::subscribe ( std::string const &  topic)

Definition at line 254 of file recorder.cpp.

◆ timeToStr()

template<class T >
std::string rosbag::Recorder::timeToStr ( ros_t)
staticprivate

Definition at line 313 of file recorder.cpp.

◆ updateFilenames()

void rosbag::Recorder::updateFilenames ( )
private

Definition at line 375 of file recorder.cpp.

Member Data Documentation

◆ bag_

Bag rosbag::Recorder::bag_
private

Definition at line 162 of file recorder.h.

◆ check_disk_mutex_

boost::mutex rosbag::Recorder::check_disk_mutex_
private

Definition at line 188 of file recorder.h.

◆ check_disk_next_

ros::WallTime rosbag::Recorder::check_disk_next_
private

Definition at line 189 of file recorder.h.

◆ current_files_

std::list<std::string> rosbag::Recorder::current_files_
private

Definition at line 166 of file recorder.h.

◆ 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

eventual exit code

Definition at line 171 of file recorder.h.

◆ last_buffer_warn_

ros::Time rosbag::Recorder::last_buffer_warn_
private

Definition at line 183 of file recorder.h.

◆ max_queue_size_

uint64_t rosbag::Recorder::max_queue_size_
private

max queue size

Definition at line 177 of file recorder.h.

◆ 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_

RecorderOptions rosbag::Recorder::options_
private

Definition at line 160 of file recorder.h.

◆ pub_begin_write

ros::Publisher rosbag::Recorder::pub_begin_write
private

Definition at line 192 of file recorder.h.

◆ queue_

std::queue<OutgoingMessage>* rosbag::Recorder::queue_
private

queue for storing

Definition at line 175 of file recorder.h.

◆ 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

mutex for queue

Definition at line 174 of file recorder.h.

◆ queue_queue_

std::queue<OutgoingQueue> rosbag::Recorder::queue_queue_
private

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

queue size

Definition at line 176 of file recorder.h.

◆ split_count_

uint64_t rosbag::Recorder::split_count_
private

split count

Definition at line 179 of file recorder.h.

◆ start_time_

ros::Time rosbag::Recorder::start_time_
private

Definition at line 185 of file recorder.h.

◆ target_filename_

std::string rosbag::Recorder::target_filename_
private

Definition at line 164 of file recorder.h.

◆ warn_next_

ros::WallTime rosbag::Recorder::warn_next_
private

Definition at line 190 of file recorder.h.

◆ write_filename_

std::string rosbag::Recorder::write_filename_
private

Definition at line 165 of file recorder.h.

◆ writing_enabled_

bool rosbag::Recorder::writing_enabled_
private

Definition at line 187 of file recorder.h.


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