Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
Aws::Rosbag::Utils::Recorder Class Reference

#include <recorder.h>

Public Member Functions

void DoTrigger ()
 
bool IsSubscribed (std::string const &topic) const
 
 Recorder (RecorderOptions options)
 
int Run ()
 
boost::shared_ptr< ros::SubscriberSubscribe (ros::NodeHandle &nh, std::string const &topic)
 

Private Member Functions

bool CheckDisk ()
 
bool CheckDuration (const ros::Time &t)
 
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, ros::Subscriber *subscriber, const 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

rosbag::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_
 
ros::NodeHandle nh_
 
RecorderOptions options_
 
ros::Publisher pub_begin_write_
 
std::shared_ptr< 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< OutgoingQueuequeue_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::vector< boost::shared_ptr< ros::Subscriber > > subscribers_
 
std::string target_filename_
 
ros::WallTime warn_next_
 
std::string write_filename_
 
bool writing_enabled_
 

Detailed Description

Definition at line 125 of file recorder.h.

Constructor & Destructor Documentation

Aws::Rosbag::Utils::Recorder::Recorder ( RecorderOptions  options)
explicit

Definition at line 101 of file recorder.cpp.

Member Function Documentation

bool Aws::Rosbag::Utils::Recorder::CheckDisk ( )
private

Definition at line 675 of file recorder.cpp.

bool Aws::Rosbag::Utils::Recorder::CheckDuration ( const ros::Time t)
private

Definition at line 443 of file recorder.cpp.

bool Aws::Rosbag::Utils::Recorder::CheckLogging ( )
private

Definition at line 731 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::CheckNumSplits ( )
private

Definition at line 406 of file recorder.cpp.

bool Aws::Rosbag::Utils::Recorder::CheckSize ( )
private

Definition at line 423 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::DoCheckMaster ( ros::TimerEvent const &  e,
ros::NodeHandle node_handle 
)
private

Definition at line 597 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::DoQueue ( const ros::MessageEvent< topic_tools::ShapeShifter const > &  msg_event,
std::string const &  topic,
ros::Subscriber subscriber,
const boost::shared_ptr< int > &  count 
)
private

Callback to be invoked to save messages into a queue.

Definition at line 272 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::DoRecord ( )
private

Thread that actually does writing to file.

Definition at line 469 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::DoRecordSnapshotter ( )
private

Definition at line 557 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::DoTrigger ( )

Definition at line 654 of file recorder.cpp.

bool Aws::Rosbag::Utils::Recorder::IsSubscribed ( std::string const &  topic) const

Definition at line 223 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::PrintUsage ( )
private
int Aws::Rosbag::Utils::Recorder::Run ( )

Definition at line 110 of file recorder.cpp.

bool Aws::Rosbag::Utils::Recorder::ScheduledCheckDisk ( )
private

Definition at line 663 of file recorder.cpp.

bool Aws::Rosbag::Utils::Recorder::ShouldSubscribeToTopic ( std::string const &  topic,
bool  from_node = false 
)
private

Definition at line 227 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::SnapshotTrigger ( std_msgs::Empty::ConstPtr  trigger)
private

Callback to be invoked to actually do the recording.

Definition at line 361 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::StartWriting ( )
private

Definition at line 377 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::StopWriting ( )
private

Definition at line 400 of file recorder.cpp.

shared_ptr< ros::Subscriber > Aws::Rosbag::Utils::Recorder::Subscribe ( ros::NodeHandle nh,
std::string const &  topic 
)

Definition at line 203 of file recorder.cpp.

template<class T >
std::string Aws::Rosbag::Utils::Recorder::TimeToStr ( ros_t)
staticprivate

Definition at line 258 of file recorder.cpp.

void Aws::Rosbag::Utils::Recorder::UpdateFilenames ( )
private

Definition at line 322 of file recorder.cpp.

Member Data Documentation

rosbag::Bag Aws::Rosbag::Utils::Recorder::bag_
private

Definition at line 171 of file recorder.h.

boost::mutex Aws::Rosbag::Utils::Recorder::check_disk_mutex_
private

Definition at line 196 of file recorder.h.

ros::WallTime Aws::Rosbag::Utils::Recorder::check_disk_next_
private

Definition at line 197 of file recorder.h.

std::list<std::string> Aws::Rosbag::Utils::Recorder::current_files_
private

Definition at line 175 of file recorder.h.

std::set<std::string> Aws::Rosbag::Utils::Recorder::currently_recording_
private

set of currenly recording topics

Definition at line 177 of file recorder.h.

int Aws::Rosbag::Utils::Recorder::exit_code_
private

eventual exit code

Definition at line 180 of file recorder.h.

ros::Time Aws::Rosbag::Utils::Recorder::last_buffer_warn_
private

Definition at line 191 of file recorder.h.

ros::NodeHandle Aws::Rosbag::Utils::Recorder::nh_
private

Definition at line 169 of file recorder.h.

RecorderOptions Aws::Rosbag::Utils::Recorder::options_
private

Definition at line 168 of file recorder.h.

ros::Publisher Aws::Rosbag::Utils::Recorder::pub_begin_write_
private

Definition at line 200 of file recorder.h.

std::shared_ptr<std::queue<OutgoingMessage> > Aws::Rosbag::Utils::Recorder::queue_
private

queue for storing

Definition at line 184 of file recorder.h.

boost::condition_variable_any Aws::Rosbag::Utils::Recorder::queue_condition_
private

conditional variable for queue

Definition at line 182 of file recorder.h.

boost::mutex Aws::Rosbag::Utils::Recorder::queue_mutex_
private

mutex for queue

Definition at line 183 of file recorder.h.

std::queue<OutgoingQueue> Aws::Rosbag::Utils::Recorder::queue_queue_
private

queue of queues to be used by the snapshot recorders

Definition at line 189 of file recorder.h.

uint64_t Aws::Rosbag::Utils::Recorder::queue_size_
private

queue size

Definition at line 185 of file recorder.h.

uint64_t Aws::Rosbag::Utils::Recorder::split_count_
private

split count

Definition at line 187 of file recorder.h.

ros::Time Aws::Rosbag::Utils::Recorder::start_time_
private

Definition at line 193 of file recorder.h.

std::vector<boost::shared_ptr<ros::Subscriber> > Aws::Rosbag::Utils::Recorder::subscribers_
private

Definition at line 178 of file recorder.h.

std::string Aws::Rosbag::Utils::Recorder::target_filename_
private

Definition at line 173 of file recorder.h.

ros::WallTime Aws::Rosbag::Utils::Recorder::warn_next_
private

Definition at line 198 of file recorder.h.

std::string Aws::Rosbag::Utils::Recorder::write_filename_
private

Definition at line 174 of file recorder.h.

bool Aws::Rosbag::Utils::Recorder::writing_enabled_
private

Definition at line 195 of file recorder.h.


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


rosbag_cloud_recorders
Author(s): AWS RoboMaker
autogenerated on Tue Jun 1 2021 02:51:28