#include <snapshotter.h>
Public Member Functions | |
int | run () |
Snapshotter (SnapshotterOptions const &options) | |
~Snapshotter () | |
Private Types | |
typedef std::map< std::string, boost::shared_ptr< MessageQueue > > | buffers_t |
Private Member Functions | |
void | clear () |
bool | enableCB (std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) |
void | fixTopicOptions (SnapshotterTopicOptions &options) |
void | pause () |
void | pollTopics (ros::TimerEvent const &e, rosbag_snapshot::SnapshotterOptions *options) |
bool | postfixFilename (std::string &file) |
void | publishStatus (ros::TimerEvent const &e) |
void | resume () |
void | subscribe (std::string const &topic, boost::shared_ptr< MessageQueue > queue) |
std::string | timeAsStr () |
Return current local datetime as a string such as 2018-05-22-14-28-51. Used to generate bag filenames. More... | |
void | topicCB (const ros::MessageEvent< topic_tools::ShapeShifter const > &msg_event, boost::shared_ptr< MessageQueue > queue) |
bool | triggerSnapshotCb (rosbag_snapshot_msgs::TriggerSnapshot::Request &req, rosbag_snapshot_msgs::TriggerSnapshot::Response &res) |
bool | writeTopic (rosbag::Bag &bag, MessageQueue &message_queue, std::string const &topic, rosbag_snapshot_msgs::TriggerSnapshot::Request &req, rosbag_snapshot_msgs::TriggerSnapshot::Response &res) |
Private Attributes | |
buffers_t | buffers_ |
ros::ServiceServer | enable_server_ |
ros::NodeHandle | nh_ |
SnapshotterOptions | options_ |
ros::Timer | poll_topic_timer_ |
bool | recording_ |
boost::upgrade_mutex | state_lock_ |
ros::Publisher | status_pub_ |
ros::Timer | status_timer_ |
ros::ServiceServer | trigger_snapshot_server_ |
bool | writing_ |
Static Private Attributes | |
static const int | QUEUE_SIZE = 10 |
Definition at line 178 of file snapshotter.h.
|
private |
Definition at line 191 of file snapshotter.h.
|
explicit |
Definition at line 224 of file snapshotter.cpp.
rosbag_snapshot::Snapshotter::~Snapshotter | ( | ) |
Definition at line 229 of file snapshotter.cpp.
|
private |
Definition at line 439 of file snapshotter.cpp.
|
private |
Definition at line 460 of file snapshotter.cpp.
|
private |
Definition at line 239 of file snapshotter.cpp.
|
private |
Definition at line 447 of file snapshotter.cpp.
|
private |
Definition at line 511 of file snapshotter.cpp.
|
private |
Definition at line 247 of file snapshotter.cpp.
|
private |
Definition at line 484 of file snapshotter.cpp.
|
private |
Definition at line 453 of file snapshotter.cpp.
int rosbag_snapshot::Snapshotter::run | ( | ) |
Definition at line 538 of file snapshotter.cpp.
|
private |
Definition at line 287 of file snapshotter.cpp.
|
private |
Return current local datetime as a string such as 2018-05-22-14-28-51. Used to generate bag filenames.
Definition at line 260 of file snapshotter.cpp.
|
private |
Definition at line 270 of file snapshotter.cpp.
|
private |
Definition at line 346 of file snapshotter.cpp.
|
private |
Definition at line 304 of file snapshotter.cpp.
|
private |
Definition at line 192 of file snapshotter.h.
|
private |
Definition at line 201 of file snapshotter.h.
|
private |
Definition at line 199 of file snapshotter.h.
|
private |
Definition at line 190 of file snapshotter.h.
|
private |
Definition at line 204 of file snapshotter.h.
|
staticprivate |
Definition at line 189 of file snapshotter.h.
|
private |
Definition at line 196 of file snapshotter.h.
|
private |
Definition at line 194 of file snapshotter.h.
|
private |
Definition at line 202 of file snapshotter.h.
|
private |
Definition at line 203 of file snapshotter.h.
|
private |
Definition at line 200 of file snapshotter.h.
|
private |
Definition at line 198 of file snapshotter.h.