rosbag::Recorder Class Reference

#include <recorder.h>

List of all members.

Public Member Functions

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

Private Member Functions

bool checkDisk ()
bool checkDuration (const ros::Time &)
bool checkLogging ()
bool checkSize ()
void doCheckMaster (ros::TimerEvent const &e, ros::NodeHandle &node_handle)
void doQueue (ros::MessageEvent< topic_tools::ShapeShifter const > msg_event, std::string const &topic, boost::shared_ptr< ros::Subscriber > subscriber, boost::shared_ptr< int > count)
void doRecord ()
 Thread that actually does writing to file.
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.
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::set< std::string > currently_recording_
 set of currenly recording topics
int exit_code_
 eventual exit code
ros::Time last_buffer_warn_
uint64_t max_queue_size_
 max queue size
int num_subscribers_
 used for book-keeping of our number of subscribers
RecorderOptions options_
std::queue< OutgoingMessage > * queue_
 queue for storing
boost::condition_variable_any queue_condition_
 conditional variable for queue
boost::mutex queue_mutex_
 mutex for queue
std::queue< OutgoingQueuequeue_queue_
 queue of queues to be used by the snapshot recorders
uint64_t queue_size_
 queue size
uint64_t split_count_
 split count
ros::Time start_time_
std::string target_filename_
ros::WallTime warn_next_
std::string write_filename_
bool writing_enabled_

Detailed Description

Definition at line 105 of file recorder.h.


Constructor & Destructor Documentation

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

Definition at line 111 of file recorder.cpp.


Member Function Documentation

bool rosbag::Recorder::checkDisk (  )  [private]

Definition at line 576 of file recorder.cpp.

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

Definition at line 389 of file recorder.cpp.

bool rosbag::Recorder::checkLogging (  )  [private]

Definition at line 600 of file recorder.cpp.

bool rosbag::Recorder::checkSize (  )  [private]

Definition at line 369 of file recorder.cpp.

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

Definition at line 508 of file recorder.cpp.

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

Thread that actually does writing to file.

Definition at line 415 of file recorder.cpp.

void rosbag::Recorder::doRecordSnapshotter (  )  [private]

Definition at line 470 of file recorder.cpp.

void rosbag::Recorder::doTrigger (  ) 

Definition at line 557 of file recorder.cpp.

bool rosbag::Recorder::isSubscribed ( std::string const &  topic  )  const
void rosbag::Recorder::printUsage (  )  [private]
int rosbag::Recorder::run (  ) 

Definition at line 121 of file recorder.cpp.

bool rosbag::Recorder::scheduledCheckDisk (  )  [private]

Definition at line 566 of file recorder.cpp.

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

Definition at line 214 of file recorder.cpp.

void rosbag::Recorder::snapshotTrigger ( std_msgs::Empty::ConstPtr  trigger  )  [private]

Callback to be invoked to actually do the recording.

Definition at line 333 of file recorder.cpp.

void rosbag::Recorder::startWriting (  )  [private]

Definition at line 348 of file recorder.cpp.

void rosbag::Recorder::stopWriting (  )  [private]

Definition at line 363 of file recorder.cpp.

boost::shared_ptr<ros::Subscriber> rosbag::Recorder::subscribe ( std::string const &  topic  ) 
template<class T >
std::string rosbag::Recorder::timeToStr ( ros_t  )  [inline, static, private]

Definition at line 248 of file recorder.cpp.

void rosbag::Recorder::updateFilenames (  )  [private]

Definition at line 305 of file recorder.cpp.


Member Data Documentation

Definition at line 146 of file recorder.h.

boost::mutex rosbag::Recorder::check_disk_mutex_ [private]

Definition at line 171 of file recorder.h.

ros::WallTime rosbag::Recorder::check_disk_next_ [private]

Definition at line 172 of file recorder.h.

std::set<std::string> rosbag::Recorder::currently_recording_ [private]

set of currenly recording topics

Definition at line 151 of file recorder.h.

eventual exit code

Definition at line 154 of file recorder.h.

Definition at line 166 of file recorder.h.

max queue size

Definition at line 160 of file recorder.h.

used for book-keeping of our number of subscribers

Definition at line 152 of file recorder.h.

Definition at line 144 of file recorder.h.

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

queue for storing

Definition at line 158 of file recorder.h.

boost::condition_variable_any rosbag::Recorder::queue_condition_ [private]

conditional variable for queue

Definition at line 156 of file recorder.h.

boost::mutex rosbag::Recorder::queue_mutex_ [private]

mutex for queue

Definition at line 157 of file recorder.h.

queue of queues to be used by the snapshot recorders

Definition at line 164 of file recorder.h.

uint64_t rosbag::Recorder::queue_size_ [private]

queue size

Definition at line 159 of file recorder.h.

uint64_t rosbag::Recorder::split_count_ [private]

split count

Definition at line 162 of file recorder.h.

ros::Time rosbag::Recorder::start_time_ [private]

Definition at line 168 of file recorder.h.

std::string rosbag::Recorder::target_filename_ [private]

Definition at line 148 of file recorder.h.

ros::WallTime rosbag::Recorder::warn_next_ [private]

Definition at line 173 of file recorder.h.

std::string rosbag::Recorder::write_filename_ [private]

Definition at line 149 of file recorder.h.

Definition at line 170 of file recorder.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


rosbag
Author(s): Jeremy Leibs (leibs@willowgarage.com), James Bowman (jamesb@willowgarage.com), Ken Conley (kwc@willowgarage.com), and Tim Field (tfield@willowgarage.com)
autogenerated on Fri Jan 11 10:11:44 2013