#include <snapshotter.h>
Public Types | |
| typedef std::map< std::string, SnapshotterTopicOptions > | topics_t |
Public Member Functions | |
| bool | addTopic (std::string const &topic, ros::Duration duration_limit=SnapshotterTopicOptions::INHERIT_DURATION_LIMIT, int32_t memory_limit=SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT, int32_t count_limit=SnapshotterTopicOptions::INHERIT_COUNT_LIMIT) |
| SnapshotterOptions (ros::Duration default_duration_limit=ros::Duration(30), int32_t default_memory_limit=-1, int32_t default_count_limit=-1, ros::Duration status_period=ros::Duration(1), bool clear_buffer=true) | |
Public Attributes | |
| bool | all_topics_ |
| bool | clear_buffer_ |
| std::string | compression_ |
| int32_t | default_count_limit_ |
| ros::Duration | default_duration_limit_ |
| int32_t | default_memory_limit_ |
| int | queue_size_ |
| ros::Duration | status_period_ |
| topics_t | topics_ |
Definition at line 124 of file snapshotter.h.
| typedef std::map<std::string, SnapshotterTopicOptions> rosbag_snapshot::SnapshotterOptions::topics_t |
Definition at line 144 of file snapshotter.h.
| rosbag_snapshot::SnapshotterOptions::SnapshotterOptions | ( | ros::Duration | default_duration_limit = ros::Duration(30), |
| int32_t | default_memory_limit = -1, |
||
| int32_t | default_count_limit = -1, |
||
| ros::Duration | status_period = ros::Duration(1), |
||
| bool | clear_buffer = true |
||
| ) |
Definition at line 71 of file snapshotter.cpp.
| bool rosbag_snapshot::SnapshotterOptions::addTopic | ( | std::string const & | topic, |
| ros::Duration | duration_limit = SnapshotterTopicOptions::INHERIT_DURATION_LIMIT, |
||
| int32_t | memory_limit = SnapshotterTopicOptions::INHERIT_MEMORY_LIMIT, |
||
| int32_t | count_limit = SnapshotterTopicOptions::INHERIT_COUNT_LIMIT |
||
| ) |
Definition at line 82 of file snapshotter.cpp.
| bool rosbag_snapshot::SnapshotterOptions::all_topics_ |
Definition at line 135 of file snapshotter.h.
| bool rosbag_snapshot::SnapshotterOptions::clear_buffer_ |
Definition at line 137 of file snapshotter.h.
| std::string rosbag_snapshot::SnapshotterOptions::compression_ |
Definition at line 139 of file snapshotter.h.
| int32_t rosbag_snapshot::SnapshotterOptions::default_count_limit_ |
Definition at line 131 of file snapshotter.h.
| ros::Duration rosbag_snapshot::SnapshotterOptions::default_duration_limit_ |
Definition at line 127 of file snapshotter.h.
| int32_t rosbag_snapshot::SnapshotterOptions::default_memory_limit_ |
Definition at line 129 of file snapshotter.h.
| int rosbag_snapshot::SnapshotterOptions::queue_size_ |
Definition at line 141 of file snapshotter.h.
| ros::Duration rosbag_snapshot::SnapshotterOptions::status_period_ |
Definition at line 133 of file snapshotter.h.
| topics_t rosbag_snapshot::SnapshotterOptions::topics_ |
Definition at line 146 of file snapshotter.h.