#include <view.h>
Classes | |
| class | iterator |
| An iterator that points to a MessageInstance from a bag. More... | |
| struct | TrueQuery |
Public Types | |
| typedef iterator | const_iterator |
Public Member Functions | |
| void | addQuery (Bag const &bag, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX) |
| Add a query to a view. | |
| void | addQuery (Bag const &bag, boost::function< bool(ConnectionInfo const *)> query, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX) |
| Add a query to a view. | |
| iterator | begin () |
| Simply copy the merge_queue state into the iterator. | |
| iterator | end () |
| Default constructed iterator signifies end. | |
| ros::Time | getBeginTime () |
| std::vector< const ConnectionInfo * > | getConnections () |
| ros::Time | getEndTime () |
| uint32_t | size () |
| View (bool const &reduce_overlap=false) | |
| Create a view on a bag. | |
| View (Bag const &bag, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX, bool const &reduce_overlap=false) | |
| Create a view on a bag. | |
| View (Bag const &bag, boost::function< bool(ConnectionInfo const *)> query, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX, bool const &reduce_overlap=false) | |
| Create a view and add a query. | |
| ~View () | |
Protected Member Functions | |
| MessageInstance * | newMessageInstance (ConnectionInfo const *connection_info, IndexEntry const &index, Bag const &bag) |
| void | update () |
| void | updateQueries (BagQuery *q) |
Protected Attributes | |
| std::vector< BagQuery * > | queries_ |
| std::vector< MessageRange * > | ranges_ |
| bool | reduce_overlap_ |
| uint32_t | size_cache_ |
| uint32_t | size_revision_ |
| uint32_t | view_revision_ |
Private Member Functions | |
| View & | operator= (View const &view) |
| View (View const &view) | |
Friends | |
| class | Bag |
| class | iterator |
| typedef iterator rosbag::View::const_iterator |
| rosbag::View::View | ( | bool const & | reduce_overlap = false | ) |
| rosbag::View::View | ( | Bag const & | bag, |
| ros::Time const & | start_time = ros::TIME_MIN, |
||
| ros::Time const & | end_time = ros::TIME_MAX, |
||
| bool const & | reduce_overlap = false |
||
| ) |
Create a view on a bag.
param bag The bag file on which to run this query param start_time The beginning of the time range for the query param end_time The end of the time range for the query param reduce_overlap If multiple views return the same messages, reduce them to a single message
| rosbag::View::View | ( | Bag const & | bag, |
| boost::function< bool(ConnectionInfo const *)> | query, | ||
| ros::Time const & | start_time = ros::TIME_MIN, |
||
| ros::Time const & | end_time = ros::TIME_MAX, |
||
| bool const & | reduce_overlap = false |
||
| ) |
Create a view and add a query.
param bag The bag file on which to run this query param query The actual query to evaluate which connections to include param start_time The beginning of the time range for the query param end_time The end of the time range for the query param reduce_overlap If multiple views return the same messages, reduce them to a single message
| rosbag::View::View | ( | View const & | view | ) | [private] |
| void rosbag::View::addQuery | ( | Bag const & | bag, |
| ros::Time const & | start_time = ros::TIME_MIN, |
||
| ros::Time const & | end_time = ros::TIME_MAX |
||
| ) |
| void rosbag::View::addQuery | ( | Bag const & | bag, |
| boost::function< bool(ConnectionInfo const *)> | query, | ||
| ros::Time const & | start_time = ros::TIME_MIN, |
||
| ros::Time const & | end_time = ros::TIME_MAX |
||
| ) |
Add a query to a view.
param bag The bag file on which to run this query param query The actual query to evaluate which connections to include param start_time The beginning of the time range for the query param end_time The end of the time range for the query
| std::vector< const ConnectionInfo * > rosbag::View::getConnections | ( | ) |
| MessageInstance * rosbag::View::newMessageInstance | ( | ConnectionInfo const * | connection_info, |
| IndexEntry const & | index, | ||
| Bag const & | bag | ||
| ) | [protected] |
| uint32_t rosbag::View::size | ( | ) |
| void rosbag::View::update | ( | ) | [protected] |
| void rosbag::View::updateQueries | ( | BagQuery * | q | ) | [protected] |
std::vector<BagQuery*> rosbag::View::queries_ [protected] |
std::vector<MessageRange*> rosbag::View::ranges_ [protected] |
bool rosbag::View::reduce_overlap_ [protected] |
uint32_t rosbag::View::size_cache_ [protected] |
uint32_t rosbag::View::size_revision_ [protected] |
uint32_t rosbag::View::view_revision_ [protected] |