#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 () |
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 currenly 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_ |
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< OutgoingQueue > | queue_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_ |
Definition at line 118 of file recorder.h.
rosbag::Recorder::Recorder | ( | RecorderOptions const & | options | ) |
Definition at line 121 of file recorder.cpp.
|
private |
Definition at line 637 of file recorder.cpp.
|
private |
Definition at line 443 of file recorder.cpp.
|
private |
Definition at line 694 of file recorder.cpp.
|
private |
Definition at line 405 of file recorder.cpp.
|
private |
Definition at line 422 of file recorder.cpp.
|
private |
Definition at line 567 of file recorder.cpp.
|
private |
Callback to be invoked to save messages into a queue.
Definition at line 287 of file recorder.cpp.
|
private |
Thread that actually does writing to file.
Definition at line 470 of file recorder.cpp.
|
private |
Definition at line 529 of file recorder.cpp.
void rosbag::Recorder::doTrigger | ( | ) |
Definition at line 618 of file recorder.cpp.
bool rosbag::Recorder::isSubscribed | ( | std::string const & | topic | ) | const |
Definition at line 235 of file recorder.cpp.
|
private |
int rosbag::Recorder::run | ( | ) |
Definition at line 131 of file recorder.cpp.
|
private |
Definition at line 627 of file recorder.cpp.
|
private |
Definition at line 239 of file recorder.cpp.
|
private |
Callback to be invoked to actually do the recording.
Definition at line 367 of file recorder.cpp.
|
private |
Definition at line 383 of file recorder.cpp.
|
private |
Definition at line 399 of file recorder.cpp.
shared_ptr< ros::Subscriber > rosbag::Recorder::subscribe | ( | std::string const & | topic | ) |
Definition at line 211 of file recorder.cpp.
|
staticprivate |
Definition at line 273 of file recorder.cpp.
|
private |
Definition at line 335 of file recorder.cpp.
|
private |
Definition at line 160 of file recorder.h.
|
private |
Definition at line 186 of file recorder.h.
|
private |
Definition at line 187 of file recorder.h.
|
private |
Definition at line 164 of file recorder.h.
|
private |
set of currenly recording topics
Definition at line 166 of file recorder.h.
|
private |
eventual exit code
Definition at line 169 of file recorder.h.
|
private |
Definition at line 181 of file recorder.h.
|
private |
max queue size
Definition at line 175 of file recorder.h.
|
private |
used for book-keeping of our number of subscribers
Definition at line 167 of file recorder.h.
|
private |
Definition at line 158 of file recorder.h.
|
private |
queue for storing
Definition at line 173 of file recorder.h.
|
private |
conditional variable for queue
Definition at line 171 of file recorder.h.
|
private |
mutex for queue
Definition at line 172 of file recorder.h.
|
private |
queue of queues to be used by the snapshot recorders
Definition at line 179 of file recorder.h.
|
private |
queue size
Definition at line 174 of file recorder.h.
|
private |
split count
Definition at line 177 of file recorder.h.
|
private |
Definition at line 183 of file recorder.h.
|
private |
Definition at line 162 of file recorder.h.
|
private |
Definition at line 188 of file recorder.h.
|
private |
Definition at line 163 of file recorder.h.
|
private |
Definition at line 185 of file recorder.h.