Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
rosbag_snapshot::Snapshotter Class Reference

#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
 

Detailed Description

Definition at line 178 of file snapshotter.h.

Member Typedef Documentation

Definition at line 191 of file snapshotter.h.

Constructor & Destructor Documentation

rosbag_snapshot::Snapshotter::Snapshotter ( SnapshotterOptions const &  options)
explicit

Definition at line 224 of file snapshotter.cpp.

rosbag_snapshot::Snapshotter::~Snapshotter ( )

Definition at line 229 of file snapshotter.cpp.

Member Function Documentation

void rosbag_snapshot::Snapshotter::clear ( )
private

Definition at line 439 of file snapshotter.cpp.

bool rosbag_snapshot::Snapshotter::enableCB ( std_srvs::SetBool::Request &  req,
std_srvs::SetBool::Response &  res 
)
private

Definition at line 460 of file snapshotter.cpp.

void rosbag_snapshot::Snapshotter::fixTopicOptions ( SnapshotterTopicOptions options)
private

Definition at line 239 of file snapshotter.cpp.

void rosbag_snapshot::Snapshotter::pause ( )
private

Definition at line 447 of file snapshotter.cpp.

void rosbag_snapshot::Snapshotter::pollTopics ( ros::TimerEvent const &  e,
rosbag_snapshot::SnapshotterOptions options 
)
private

Definition at line 511 of file snapshotter.cpp.

bool rosbag_snapshot::Snapshotter::postfixFilename ( std::string &  file)
private

Definition at line 247 of file snapshotter.cpp.

void rosbag_snapshot::Snapshotter::publishStatus ( ros::TimerEvent const &  e)
private

Definition at line 484 of file snapshotter.cpp.

void rosbag_snapshot::Snapshotter::resume ( )
private

Definition at line 453 of file snapshotter.cpp.

int rosbag_snapshot::Snapshotter::run ( )

Definition at line 538 of file snapshotter.cpp.

void rosbag_snapshot::Snapshotter::subscribe ( std::string const &  topic,
boost::shared_ptr< MessageQueue queue 
)
private

Definition at line 287 of file snapshotter.cpp.

string rosbag_snapshot::Snapshotter::timeAsStr ( )
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.

void rosbag_snapshot::Snapshotter::topicCB ( const ros::MessageEvent< topic_tools::ShapeShifter const > &  msg_event,
boost::shared_ptr< MessageQueue queue 
)
private

Definition at line 270 of file snapshotter.cpp.

bool rosbag_snapshot::Snapshotter::triggerSnapshotCb ( rosbag_snapshot_msgs::TriggerSnapshot::Request &  req,
rosbag_snapshot_msgs::TriggerSnapshot::Response &  res 
)
private

Definition at line 346 of file snapshotter.cpp.

bool rosbag_snapshot::Snapshotter::writeTopic ( rosbag::Bag bag,
MessageQueue message_queue,
std::string const &  topic,
rosbag_snapshot_msgs::TriggerSnapshot::Request &  req,
rosbag_snapshot_msgs::TriggerSnapshot::Response &  res 
)
private

Definition at line 304 of file snapshotter.cpp.

Member Data Documentation

buffers_t rosbag_snapshot::Snapshotter::buffers_
private

Definition at line 192 of file snapshotter.h.

ros::ServiceServer rosbag_snapshot::Snapshotter::enable_server_
private

Definition at line 201 of file snapshotter.h.

ros::NodeHandle rosbag_snapshot::Snapshotter::nh_
private

Definition at line 199 of file snapshotter.h.

SnapshotterOptions rosbag_snapshot::Snapshotter::options_
private

Definition at line 190 of file snapshotter.h.

ros::Timer rosbag_snapshot::Snapshotter::poll_topic_timer_
private

Definition at line 204 of file snapshotter.h.

const int rosbag_snapshot::Snapshotter::QUEUE_SIZE = 10
staticprivate

Definition at line 189 of file snapshotter.h.

bool rosbag_snapshot::Snapshotter::recording_
private

Definition at line 196 of file snapshotter.h.

boost::upgrade_mutex rosbag_snapshot::Snapshotter::state_lock_
private

Definition at line 194 of file snapshotter.h.

ros::Publisher rosbag_snapshot::Snapshotter::status_pub_
private

Definition at line 202 of file snapshotter.h.

ros::Timer rosbag_snapshot::Snapshotter::status_timer_
private

Definition at line 203 of file snapshotter.h.

ros::ServiceServer rosbag_snapshot::Snapshotter::trigger_snapshot_server_
private

Definition at line 200 of file snapshotter.h.

bool rosbag_snapshot::Snapshotter::writing_
private

Definition at line 198 of file snapshotter.h.


The documentation for this class was generated from the following files:


rosbag_snapshot
Author(s): Kevin Allen
autogenerated on Mon Jan 18 2021 03:45:11