Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Friends
rosbag::View Class Reference

#include <view.h>

List of all members.

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

MessageInstancenewMessageInstance (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

Viewoperator= (View const &view)
 View (View const &view)

Friends

class Bag
class iterator

Detailed Description

Definition at line 48 of file view.h.


Member Typedef Documentation

Definition at line 92 of file view.h.


Constructor & Destructor Documentation

rosbag::View::View ( bool const &  reduce_overlap = false)

Create a view on a bag.

param reduce_overlap If multiple views return the same messages, reduce them to a single message

Definition at line 156 of file view.cpp.

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

Definition at line 158 of file view.cpp.

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

Definition at line 162 of file view.cpp.

Definition at line 166 of file view.cpp.

rosbag::View::View ( View const &  view) [private]

Member Function Documentation

void rosbag::View::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.

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

Definition at line 235 of file view.cpp.

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

Definition at line 246 of file view.cpp.

Simply copy the merge_queue state into the iterator.

Definition at line 208 of file view.cpp.

Default constructed iterator signifies end.

Definition at line 214 of file view.cpp.

Definition at line 174 of file view.cpp.

std::vector< const ConnectionInfo * > rosbag::View::getConnections ( )

Definition at line 318 of file view.cpp.

Definition at line 189 of file view.cpp.

MessageInstance * rosbag::View::newMessageInstance ( ConnectionInfo const *  connection_info,
IndexEntry const &  index,
Bag const &  bag 
) [protected]

Definition at line 330 of file view.cpp.

View& rosbag::View::operator= ( View const &  view) [private]
uint32_t rosbag::View::size ( )

Definition at line 216 of file view.cpp.

void rosbag::View::update ( ) [protected]

Definition at line 309 of file view.cpp.

void rosbag::View::updateQueries ( BagQuery q) [protected]

Definition at line 255 of file view.cpp.


Friends And Related Function Documentation

friend class Bag [friend]

Definition at line 50 of file view.h.

friend class iterator [friend]

Definition at line 154 of file view.h.


Member Data Documentation

std::vector<BagQuery*> rosbag::View::queries_ [protected]

Definition at line 167 of file view.h.

std::vector<MessageRange*> rosbag::View::ranges_ [protected]

Definition at line 166 of file view.h.

Definition at line 173 of file view.h.

uint32_t rosbag::View::size_cache_ [protected]

Definition at line 170 of file view.h.

uint32_t rosbag::View::size_revision_ [protected]

Definition at line 171 of file view.h.

uint32_t rosbag::View::view_revision_ [protected]

Definition at line 168 of file view.h.


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


rosbag_storage
Author(s):
autogenerated on Thu Jun 6 2019 21:09:52