message_instance.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef ROSBAG_MESSAGE_INSTANCE_H
36 #define ROSBAG_MESSAGE_INSTANCE_H
37 
38 #include <ros/message_traits.h>
39 #include <ros/serialization.h>
40 //#include <ros/ros.h>
41 #include <ros/time.h>
42 #include <memory.h>
43 #include "rosbag/structures.h"
44 #include "rosbag/macros.h"
45 
46 namespace rosbag {
47 
48 class Bag;
49 
51 
60 {
61  friend class View;
62 
63 public:
64  rs2rosinternal::Time const& getTime() const;
65  std::string const& getTopic() const;
66  std::string const& getDataType() const;
67  std::string const& getMD5Sum() const;
68  std::string const& getMessageDefinition() const;
69 
70  std::shared_ptr<rs2rosinternal::M_string> getConnectionHeader() const;
71 
72  std::string getCallerId() const;
73  bool isLatching() const;
74 
76 
79  template<class T>
80  bool isType() const;
81 
83 
86  template<class T>
87  std::shared_ptr<T> instantiate() const;
88 
90  template<typename Stream>
91  void write(Stream& stream) const;
92 
94  uint32_t size() const;
95 
96 private:
97  MessageInstance(ConnectionInfo const* connection_info, IndexEntry const& index, Bag const& bag);
98 
101  Bag const* bag_;
102 };
103 
104 
105 } // namespace rosbag
106 
107 namespace rs2rosinternal {
108 namespace message_traits {
109 
110 template<>
111 struct MD5Sum<rosbag::MessageInstance>
112 {
113  static const char* value(const rosbag::MessageInstance& m) { return m.getMD5Sum().c_str(); }
114 };
115 
116 template<>
117 struct DataType<rosbag::MessageInstance>
118 {
119  static const char* value(const rosbag::MessageInstance& m) { return m.getDataType().c_str(); }
120 };
121 
122 template<>
123 struct Definition<rosbag::MessageInstance>
124 {
125  static const char* value(const rosbag::MessageInstance& m) { return m.getMessageDefinition().c_str(); }
126 };
127 
128 } // namespace message_traits
129 
130 namespace serialization
131 {
132 
133 template<>
134 struct Serializer<rosbag::MessageInstance>
135 {
136  template<typename Stream>
137  inline static void write(Stream& stream, const rosbag::MessageInstance& m) {
138  m.write(stream);
139  }
140 
142  return m.size();
143  }
144 };
145 
146 } // namespace serialization
147 
148 } // namespace rs2rosinternal
149 
150 #include "rosbag/bag.h"
151 
152 namespace rosbag {
153 
154 template<class T>
157  return md5sum == std::string("*") || md5sum == getMD5Sum();
158 }
159 
160 template<class T>
161 std::shared_ptr<T> MessageInstance::instantiate() const {
162  if (!isType<T>())
163  return std::shared_ptr<T>();
164 
165  return bag_->instantiateBuffer<T>(index_entry_);
166 }
167 
168 template<typename Stream>
170  bag_->readMessageDataIntoStream(index_entry_, stream);
171 }
172 
173 } // namespace rosbag
174 
175 #endif
const char * md5sum()
returns MD5Sum<M>::value();
ConnectionInfo const * connection_info_
const GLfloat * m
Definition: glext.h:6814
Specialize to provide the md5sum for a message.
IndexEntry const index_entry_
static const char * value(const rosbag::MessageInstance &m)
GLsizei const GLchar *const * string
std::string const & getMD5Sum() const
Specialize to provide the datatype for a message.
GLuint GLuint stream
Definition: glext.h:1790
GLuint index
Stream base-class, provides common functionality for IStream and OStream.
GLsizeiptr size
bool isType() const
Test whether the underlying message of the specified type.
unsigned int uint32_t
Definition: stdint.h:80
A class pointing into a bag file.
uint32_t size() const
Size of serialized message.
static const char * value(const rosbag::MessageInstance &m)
static void write(Stream &stream, const rosbag::MessageInstance &m)
Time representation. May either represent wall clock time or ROS clock time.
Definition: time.h:177
Specialize to provide the definition for a message.
std::string const & getMessageDefinition() const
static const char * value(const rosbag::MessageInstance &m)
Definition: bag.h:66
std::string const & getDataType() const
static uint32_t serializedLength(const rosbag::MessageInstance &m)
Templated serialization class. Default implementation provides backwards compatibility with old messa...
std::shared_ptr< T > instantiate() const
Templated call to instantiate a message.
#define ROSBAG_DECL
#include <ros/macros.h> // for the DECL&#39;s
void write(Stream &stream) const
Write serialized message contents out to a stream.


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:21