#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::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) |
Callback to be invoked to save messages into a queue. | |
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< OutgoingQueue > | queue_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_ |
Definition at line 113 of file recorder.h.
rosbag::Recorder::Recorder | ( | RecorderOptions const & | options | ) |
Definition at line 118 of file recorder.cpp.
bool rosbag::Recorder::checkDisk | ( | ) | [private] |
Definition at line 592 of file recorder.cpp.
bool rosbag::Recorder::checkDuration | ( | const ros::Time & | t | ) | [private] |
Definition at line 401 of file recorder.cpp.
bool rosbag::Recorder::checkLogging | ( | ) | [private] |
Definition at line 649 of file recorder.cpp.
bool rosbag::Recorder::checkSize | ( | ) | [private] |
Definition at line 381 of file recorder.cpp.
void rosbag::Recorder::doCheckMaster | ( | ros::TimerEvent const & | e, |
ros::NodeHandle & | node_handle | ||
) | [private] |
Definition at line 524 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] |
Callback to be invoked to save messages into a queue.
Definition at line 268 of file recorder.cpp.
void rosbag::Recorder::doRecord | ( | ) | [private] |
Thread that actually does writing to file.
Definition at line 427 of file recorder.cpp.
void rosbag::Recorder::doRecordSnapshotter | ( | ) | [private] |
Definition at line 486 of file recorder.cpp.
void rosbag::Recorder::doTrigger | ( | ) |
Definition at line 573 of file recorder.cpp.
bool rosbag::Recorder::isSubscribed | ( | std::string const & | topic | ) | const |
Definition at line 217 of file recorder.cpp.
void rosbag::Recorder::printUsage | ( | ) | [private] |
int rosbag::Recorder::run | ( | ) |
Definition at line 128 of file recorder.cpp.
bool rosbag::Recorder::scheduledCheckDisk | ( | ) | [private] |
Definition at line 582 of file recorder.cpp.
bool rosbag::Recorder::shouldSubscribeToTopic | ( | std::string const & | topic, |
bool | from_node = false |
||
) | [private] |
Definition at line 221 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 344 of file recorder.cpp.
void rosbag::Recorder::startWriting | ( | ) | [private] |
Definition at line 359 of file recorder.cpp.
void rosbag::Recorder::stopWriting | ( | ) | [private] |
Definition at line 375 of file recorder.cpp.
shared_ptr< ros::Subscriber > rosbag::Recorder::subscribe | ( | std::string const & | topic | ) |
Definition at line 204 of file recorder.cpp.
std::string rosbag::Recorder::timeToStr | ( | T | ros_t | ) | [static, private] |
Definition at line 255 of file recorder.cpp.
void rosbag::Recorder::updateFilenames | ( | ) | [private] |
Definition at line 316 of file recorder.cpp.
Bag rosbag::Recorder::bag_ [private] |
Definition at line 154 of file recorder.h.
boost::mutex rosbag::Recorder::check_disk_mutex_ [private] |
Definition at line 179 of file recorder.h.
Definition at line 180 of file recorder.h.
std::set<std::string> rosbag::Recorder::currently_recording_ [private] |
set of currenly recording topics
Definition at line 159 of file recorder.h.
int rosbag::Recorder::exit_code_ [private] |
eventual exit code
Definition at line 162 of file recorder.h.
ros::Time rosbag::Recorder::last_buffer_warn_ [private] |
Definition at line 174 of file recorder.h.
uint64_t rosbag::Recorder::max_queue_size_ [private] |
max queue size
Definition at line 168 of file recorder.h.
int rosbag::Recorder::num_subscribers_ [private] |
used for book-keeping of our number of subscribers
Definition at line 160 of file recorder.h.
RecorderOptions rosbag::Recorder::options_ [private] |
Definition at line 152 of file recorder.h.
std::queue<OutgoingMessage>* rosbag::Recorder::queue_ [private] |
queue for storing
Definition at line 166 of file recorder.h.
boost::condition_variable_any rosbag::Recorder::queue_condition_ [private] |
conditional variable for queue
Definition at line 164 of file recorder.h.
boost::mutex rosbag::Recorder::queue_mutex_ [private] |
mutex for queue
Definition at line 165 of file recorder.h.
std::queue<OutgoingQueue> rosbag::Recorder::queue_queue_ [private] |
queue of queues to be used by the snapshot recorders
Definition at line 172 of file recorder.h.
uint64_t rosbag::Recorder::queue_size_ [private] |
queue size
Definition at line 167 of file recorder.h.
uint64_t rosbag::Recorder::split_count_ [private] |
split count
Definition at line 170 of file recorder.h.
ros::Time rosbag::Recorder::start_time_ [private] |
Definition at line 176 of file recorder.h.
std::string rosbag::Recorder::target_filename_ [private] |
Definition at line 156 of file recorder.h.
ros::WallTime rosbag::Recorder::warn_next_ [private] |
Definition at line 181 of file recorder.h.
std::string rosbag::Recorder::write_filename_ [private] |
Definition at line 157 of file recorder.h.
bool rosbag::Recorder::writing_enabled_ [private] |
Definition at line 178 of file recorder.h.