|
def | __contains__ (self, key) |
|
def | __init__ (self, *args, **kwargs) |
|
def | __next__ (self) |
|
def | close (self) |
|
def | closed (self) |
|
def | get_end_time (self) |
|
def | get_message_class (self, typename, typehash=None) |
|
def | get_message_definition (self, msg_or_type) |
|
def | get_message_type_hash (self, msg_or_type) |
|
def | get_start_time (self) |
|
def | get_topic_info (self, *_, **__) |
|
def | open (self) |
|
def | read_messages (self, topics=None, start_time=None, end_time=None, raw=False, connection_filter=None, **__) |
|
def | topics (self) |
|
def | write (self, topic, msg, t=None, raw=False, connection_header=None, **__) |
|
| Bag () |
|
| Bag (Bag &&other) |
|
| Bag (std::string const &filename, uint32_t mode=bagmode::Read) |
|
void | close () |
|
uint32_t | getChunkThreshold () const |
|
CompressionType | getCompression () const |
|
std::string | getFileName () const |
|
uint32_t | getMajorVersion () const |
|
uint32_t | getMinorVersion () const |
|
BagMode | getMode () const |
|
uint64_t | getSize () const |
|
bool | isOpen () const |
|
void | open (std::string const &filename, uint32_t mode=bagmode::Read) |
|
Bag & | operator= (Bag &&other) |
|
void | setChunkThreshold (uint32_t chunk_threshold) |
|
void | setCompression (CompressionType compression) |
|
void | setEncryptorPlugin (const std::string &plugin_name, const std::string &plugin_param=std::string()) |
|
void | swap (Bag &) |
|
void | write (std::string const &topic, ros::MessageEvent< T > const &event) |
|
void | write (std::string const &topic, ros::Time const &time, boost::shared_ptr< T > const &msg, boost::shared_ptr< ros::M_string > connection_header=boost::shared_ptr< ros::M_string >()) |
|
void | write (std::string const &topic, ros::Time const &time, boost::shared_ptr< T const > const &msg, boost::shared_ptr< ros::M_string > connection_header=boost::shared_ptr< ros::M_string >()) |
|
void | write (std::string const &topic, ros::Time const &time, T const &msg, boost::shared_ptr< ros::M_string > connection_header=boost::shared_ptr< ros::M_string >()) |
|
| ~Bag () |
|
def | __bool__ (self) |
|
def | __copy__ (self) |
|
def | __deepcopy__ (self, memo=None) |
|
def | __enter__ (self) |
|
def | __exit__ (self, exc_type, exc_value, traceback) |
|
def | __getitem__ (self, key) |
|
def | __iter__ (self) |
|
def | __len__ (self) |
|
def | __nonzero__ (self) |
|
def | __str__ (self) |
|
def | filename (self) |
|
def | flush (self) |
|
def | get_message_count (self, topic_filters=None) |
|
def | get_qoses (self, topic, typename) |
|
def | get_topic_info (self, counts=True) |
|
def | get_type_and_topic_info (self, topic_filters=None) |
|
def | mode (self) |
|
def | read_messages (self, topics=None, start_time=None, end_time=None, raw=False, **__) |
|
def | size (self) |
|
def | stop_on_error (self) |
|
def | stop_on_error (self, flag) |
|
def | write (self, topic, msg, t=None, raw=False, **kwargs) |
|
|
| BagMessage = collections.namedtuple("BagMessage", "topic message timestamp") |
| Returned from read_messages() as (topic name, ROS message, ROS timestamp object). More...
|
|
tuple | MODES = ("r", "w", "a") |
| Supported opening modes, overridden in subclasses. More...
|
|
| next |
|
bool | STREAMABLE = True |
| Whether bag supports reading or writing stream objects, overridden in subclasses. More...
|
|
| TopicTuple |
| Returned from get_type_and_topic_info() as (typename, message count, connection count, median frequency). More...
|
|
| TypesAndTopicsTuple = collections.namedtuple("TypesAndTopicsTuple", ["msg_types", "topics"]) |
| Returned from get_type_and_topic_info() as ({typename: typehash}, {topic name: TopicTuple}). More...
|
|
ROS1 bag reader and writer.
Extends `rosbag.Bag` with more conveniences, smooths over the rosbag bug of ignoring
topic and time filters in format v1.2, and smooths over the rosbag bug
of yielding messages of wrong type, if message types in different topics
have different packages but identical fields and hashes.
Does **not** smooth over the rosbag bug of writing different types to one topic.
rosbag does allow writing messages of different types to one topic,
just like live ROS topics can have multiple message types published
to one topic. And their serialized bytes will actually be in the bag,
but rosbag will only register the first type for this topic (unless it is
explicitly given another connection header with metadata on the other type).
All messages yielded will be deserialized by rosbag as that first type,
and whether reading will raise an exception or not depends on whether
the other type has enough bytes to be deserialized as that first type.
Definition at line 67 of file ros1.py.
def grepros.ros1.ROS1Bag.__init__ |
( |
|
self, |
|
|
* |
args, |
|
|
** |
kwargs |
|
) |
| |
@param f bag file path, or a stream object
@param mode mode to open bag in, defaults to "r" (read mode)
@param reindex if true and bag is unindexed, make a copy
of the file (unless unindexed format) and reindex original
@param progress show progress bar with reindexing status
@param kwargs additional keyword arguments for `rosbag.Bag`, like `compression`
Definition at line 99 of file ros1.py.
def grepros.ros1.ROS1Bag.read_messages |
( |
|
self, |
|
|
|
topics = None , |
|
|
|
start_time = None , |
|
|
|
end_time = None , |
|
|
|
raw = False , |
|
|
|
connection_filter = None , |
|
|
** |
__ |
|
) |
| |
Yields messages from the bag, optionally filtered by topic, timestamp and connection details.
@param topics list of topics or a single topic.
If an empty list is given, all topics will be read.
@param start_time earliest timestamp of messages to return,
as ROS time or convertible (int/float/duration/datetime/decimal)
@param end_time latest timestamp of messages to return,
as ROS time or convertible (int/float/duration/datetime/decimal)
@param connection_filter function to filter connections to include
@param raw if true, then returned messages are tuples of
(typename, bytes, typehash, typeclass)
or (typename, bytes, typehash, position, typeclass),
depending on file format
@return BagMessage namedtuples of
(topic, message, timestamp as rospy.Time)
Definition at line 193 of file ros1.py.
def grepros.ros1.ROS1Bag.write |
( |
|
self, |
|
|
|
topic, |
|
|
|
msg, |
|
|
|
t = None , |
|
|
|
raw = False , |
|
|
|
connection_header = None , |
|
|
** |
__ |
|
) |
| |
Writes a message to the bag.
Populates connection header if topic already in bag but with a different message type.
@param topic name of topic
@param msg ROS1 message
@param t message timestamp if not using current wall time,
as ROS time or convertible (int/float/duration/datetime/decimal)
@param raw if true, `msg` is in raw format,
(typename, bytes, typehash, typeclass)
@param connection_header custom connection record for topic,
as {"topic", "type", "md5sum", "message_definition"}
Definition at line 256 of file ros1.py.