print_helpers.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2017 Intel Corporation. All Rights Reserved.
3 
4 #pragma once
5 
6 #include <string>
7 #include <sstream>
8 #include <chrono>
9 #include <iomanip>
10 #include <array>
11 
12 #include "../../third-party/realsense-file/rosbag/rosbag_storage/include/rosbag/bag.h"
13 #include "../../third-party/realsense-file/rosbag/msgs/sensor_msgs/Imu.h"
14 #include "../../third-party/realsense-file/rosbag/msgs/sensor_msgs/Image.h"
15 #include "../../third-party/realsense-file/rosbag/msgs/diagnostic_msgs/KeyValue.h"
16 #include "../../third-party/realsense-file/rosbag/msgs/std_msgs/UInt32.h"
17 #include "../../third-party/realsense-file/rosbag/msgs/std_msgs/String.h"
18 #include "../../third-party/realsense-file/rosbag/msgs/std_msgs/Float32.h"
19 #include "../../third-party/realsense-file/rosbag/msgs/realsense_msgs/StreamInfo.h"
20 #include "../../third-party/realsense-file/rosbag/msgs/realsense_msgs/ImuIntrinsic.h"
21 #include "../../third-party/realsense-file/rosbag/msgs/sensor_msgs/CameraInfo.h"
22 #include "../../third-party/realsense-file/rosbag/msgs/sensor_msgs/TimeReference.h"
23 #include "../../third-party/realsense-file/rosbag/msgs/geometry_msgs/Transform.h"
24 #include "../../third-party/realsense-file/rosbag/msgs/geometry_msgs/Twist.h"
25 #include "../../third-party/realsense-file/rosbag/msgs/geometry_msgs/Accel.h"
26 #include "../../third-party/realsense-file/rosbag/msgs/realsense_legacy_msgs/legacy_headers.h"
27 
28 namespace rosbag_inspector
29 {
31  {
32  std::ostringstream ss;
33  template<class T> tmpstringstream & operator << (const T & val) { ss << val; return *this; }
34  operator std::string() const { return ss.str(); }
35  };
36 
38  {
39  auto hhh = std::chrono::duration_cast<std::chrono::hours>(d);
40  d -= hhh;
41  auto mm = std::chrono::duration_cast<std::chrono::minutes>(d);
42  d -= mm;
43  auto ss = std::chrono::duration_cast<std::chrono::seconds>(d);
44  d -= ss;
45  auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(d);
46 
47  std::ostringstream stream;
48  stream << std::setfill('0') << std::setw(3) << hhh.count() << ':' <<
49  std::setfill('0') << std::setw(2) << mm.count() << ':' <<
50  std::setfill('0') << std::setw(2) << ss.count() << '.' <<
51  std::setfill('0') << std::setw(3) << ms.count();
52  return stream.str();
53  }
54 
55 
56  // Streamers
57 
58 
59  template <typename Container>
60  std::ostream& print_container(std::ostream& os, const Container& c)
61  {
62  for (size_t i = 0; i < c.size(); ++i)
63  {
64  if (i != 0)
65  os << ",";
66  os << c[i];
67  }
68  return os;
69  }
70 
71  template <size_t N, typename T>
72  std::ostream& operator<<(std::ostream& os, const std::array<T, N>& arr)
73  {
74  return print_container(os, arr);
75  }
76 
77  template <typename T>
78  std::ostream& operator<<(std::ostream& os, const std::vector<T>& v)
79  {
80  return print_container(os, v);
81  }
82 
83  std::ostream& operator<<(std::ostream& os, rosbag::compression::CompressionType c)
84  {
85  switch (c)
86  {
87  case rosbag::CompressionType::Uncompressed: os << "Uncompressed"; break;
88  case rosbag::CompressionType::BZ2: os << "BZ2"; break;
89  case rosbag::CompressionType::LZ4: os << "LZ4"; break;
90  default: break;
91  }
92  return os;
93  }
94 
95  template <typename ROS_TYPE>
96  inline typename ROS_TYPE::ConstPtr try_instantiate(const rosbag::MessageInstance& m)
97  {
98  if(m.isType<ROS_TYPE>())
99  return m.instantiate<ROS_TYPE>();
100  return nullptr;
101  }
102 
103  std::ostream& operator<<(std::ostream& os, const rosbag::MessageInstance& m)
104  {
105  if (auto data = try_instantiate<std_msgs::UInt32>(m))
106  {
107  os << "Value : " << data->data << std::endl;
108  }
109  else if (auto data = try_instantiate<std_msgs::String>(m))
110  {
111  os << "Value : " << data->data << std::endl;
112  }
113  else if (auto data = try_instantiate<std_msgs::Float32>(m))
114  {
115  os << "Value : " << data->data << std::endl;
116  }
117  else if (auto data = try_instantiate<diagnostic_msgs::KeyValue>(m))
118  {
119  auto kvp = data;
120  os << "Key : " << kvp->key << std::endl;
121  os << "Value : " << kvp->value << std::endl;
122  }
123  else if (auto data = try_instantiate<realsense_msgs::StreamInfo>(m))
124  {
125  auto stream_info = data;
126  os << "Encoding : " << stream_info->encoding << std::endl;
127  os << "FPS : " << stream_info->fps << std::endl;
128  os << "Is Recommended : " << (stream_info->is_recommended ? "True" : "False") << std::endl;
129  }
130  else if (auto data = try_instantiate<sensor_msgs::CameraInfo>(m))
131  {
132  auto camera_info = data;
133  os << "Width : " << camera_info->width << std::endl;
134  os << "Height : " << camera_info->height << std::endl;
135  os << "Intrinsics : " << std::endl;
136  os << " Focal Point : " << camera_info->K[0] << ", " << camera_info->K[4] << std::endl;
137  os << " Principal Point : " << camera_info->K[2] << ", " << camera_info->K[5] << std::endl;
138  os << " Coefficients : "
139  << camera_info->D[0] << ", "
140  << camera_info->D[1] << ", "
141  << camera_info->D[2] << ", "
142  << camera_info->D[3] << ", "
143  << camera_info->D[4] << std::endl;
144  os << " Distortion Model : " << camera_info->distortion_model << std::endl;
145  }
146  else if (auto data = try_instantiate<realsense_msgs::ImuIntrinsic>(m))
147  {
148  os << "bias_variances : " << data->bias_variances << '\n';
149  os << "data : " << data->data << '\n';
150  os << "noise_variances : " << data->noise_variances << '\n';
151  }
152  else if (auto data = try_instantiate<sensor_msgs::Image>(m))
153  {
154  auto image = data;
155  os << "Header : \n";
156  os << " frame_id : " << image->header.frame_id << std::endl;
157  os << " Frame Number (seq) : " << image->header.seq << std::endl;
158  os << " stamp : " << image->header.stamp << std::endl;
159  os << "Encoding : " << image->encoding << std::endl;
160  os << "Width : " << image->width << std::endl;
161  os << "Height : " << image->height << std::endl;
162  os << "Step : " << image->step << std::endl;
163  //os << "Frame Number : " << image->header.seq << std::endl;
164  //os << "Timestamp : " << pretty_time(std::chrono::nanoseconds(image->header.stamp.toNSec())) << std::endl;
165  }
166  else if (auto data = try_instantiate<sensor_msgs::Imu>(m))
167  {
168  auto imu = data;
169  os << "header : " << imu->header << '\n';
170  os << "orientation : " << imu->orientation << '\n';
171  os << "orientation_covariance : " << imu->orientation_covariance << '\n';
172  os << "angular_velocity : " << imu->angular_velocity << '\n';
173  os << "angular_velocity_covariance : " << imu->angular_velocity_covariance << '\n';
174  os << "linear_acceleration : " << imu->linear_acceleration << '\n';
175  os << "linear_acceleration_covariance : " << imu->linear_acceleration_covariance << '\n';
176  os << "orientation_covariance : " << imu->orientation_covariance << '\n';
177  os << "angular_velocity_covariance : " << imu->angular_velocity_covariance << '\n';
178  os << "linear_acceleration_covariance : " << imu->linear_acceleration_covariance << '\n';
179  }
180  else if (auto data = try_instantiate<sensor_msgs::TimeReference>(m))
181  {
182  auto tr = data;
183  os << " Header : " << tr->header << std::endl;
184  os << " Source : " << tr->source << std::endl;
185  os << " TimeReference : " << tr->time_ref << std::endl;
186  }
187  else if (auto data = try_instantiate<geometry_msgs::Transform>(m))
188  {
189  auto tf = data;
190  os << " Rotation : " << tf->rotation << std::endl;
191  os << " Translation : " << tf->translation << std::endl;
192  }
193  else if (try_instantiate<geometry_msgs::Twist>(m) || try_instantiate<geometry_msgs::Accel>(m))
194  {
195  if (m.getDataType().find("Twist") != std::string::npos)
196  {
197  auto twist = try_instantiate<geometry_msgs::Twist>(m);
198  os << "Angular Velocity: " << twist->angular << std::endl;
199  os << "Linear Velocity: " << twist->linear << std::endl;
200  }
201  if (m.getDataType().find("Accel") != std::string::npos)
202  {
203  auto accel = try_instantiate<geometry_msgs::Accel>(m);
204  os << "Angular Acceleration: " << accel->angular << std::endl;
205  os << "Linear Acceleration: " << accel->linear << std::endl;
206  }
207  }
208 
209  /*************************************************************/
210  /*************************************************************/
211  /* Legacy Messages */
212  /*************************************************************/
213  /*************************************************************/
214 
215  else if (auto data = try_instantiate<realsense_legacy_msgs::compressed_frame_info>(m))
216  {
217  os << "encoding: " << data->encoding << '\n';
218  os << "frame_metadata: " << data->frame_metadata << '\n';
219  os << "height: " << data->height << '\n';
220  os << "step: " << data->step << '\n';
221  os << "system_time: " << data->system_time << '\n';
222  os << "time_stamp_domain: " << data->time_stamp_domain << '\n';
223  os << "width: " << data->width << '\n';
224  }
225  else if (auto data = try_instantiate<realsense_legacy_msgs::controller_command>(m))
226  {
227  os << "controller_id : " << data->controller_id << '\n';
228  os << "mac_address : " << data->mac_address << '\n';
229  os << "type : " << data->type << '\n';
230  }
231  else if (auto data = try_instantiate<realsense_legacy_msgs::controller_event>(m))
232  {
233  os << "controller_id : " << data->controller_id << '\n';
234  os << "mac_address : " << data->mac_address << '\n';
235  os << "type : " << data->type << '\n';
236  os << "timestamp : " << data->timestamp << '\n';
237  }
238  else if (auto data = try_instantiate<realsense_legacy_msgs::controller_vendor_data>(m))
239  {
240  os << "controller_id : " << data->controller_id << '\n';
241  os << "data : " << data->data << '\n';
242  os << "timestamp : " << data->timestamp << '\n';
243  os << "vendor_data_source_index : " << data->vendor_data_source_index << '\n';
244  os << "vendor_data_source_type : " << data->vendor_data_source_type << '\n';
245  }
246  else if (auto data = try_instantiate<realsense_legacy_msgs::extrinsics>(m))
247  {
248  os << " Extrinsics : " << std::endl;
249  os << " Rotation : " << data->rotation << std::endl;
250  os << " Translation : " << data->translation << std::endl;
251  }
252  else if (auto data = try_instantiate<realsense_legacy_msgs::frame_info>(m))
253  {
254  os << "frame_metadata :" << data->frame_metadata << '\n';
255  os << "system_time :" << data->system_time << '\n';
256  os << "time_stamp_domain :" << data->time_stamp_domain << '\n';
257  }
258  else if (auto data = try_instantiate<realsense_legacy_msgs::metadata>(m))
259  {
260  os << "type : " << data->type << '\n';
261  os << "data : " << data->data << '\n';
262  }
263  else if (auto data = try_instantiate<realsense_legacy_msgs::motion_intrinsics>(m))
264  {
265  os << "bias_variances : " << data->bias_variances << '\n';
266  os << "data : " << data->data << '\n';
267  os << "noise_variances : " << data->noise_variances << '\n';
268  }
269  else if (auto data = try_instantiate<realsense_legacy_msgs::motion_stream_info>(m))
270  {
271  os << "fps : " << data->fps << '\n';
272  os << "motion_type : " << data->motion_type << '\n';
273  os << "stream_extrinsics : " << data->stream_extrinsics << '\n';
274  os << "stream_intrinsics : " << data->stream_intrinsics << '\n';
275  }
276  else if (auto data = try_instantiate<realsense_legacy_msgs::occupancy_map>(m))
277  {
278  os << "accuracy : " << data->accuracy << '\n';
279  os << "reserved : " << data->reserved << '\n';
280  os << "tiles : " << data->tiles << '\n';
281  os << "tile_count : " << data->tile_count << '\n';
282  }
283  else if (auto data = try_instantiate<realsense_legacy_msgs::pose>(m))
284  {
285  os << "translation : " << data->translation << '\n';
286  os << "rotation : " << data->rotation << '\n';
287  os << "velocity : " << data->velocity << '\n';
288  os << "angular_velocity : " << data->angular_velocity << '\n';
289  os << "acceleration : " << data->acceleration << '\n';
290  os << "angular_acceleration : " << data->angular_acceleration << '\n';
291  os << "timestamp : " << data->timestamp << '\n';
292  os << "system_timestamp : " << data->system_timestamp << '\n';
293  }
294  else if (auto data = try_instantiate<realsense_legacy_msgs::stream_extrinsics>(m))
295  {
296  os << "extrinsics : " << data->extrinsics << '\n';
297  os << "reference_point_id : " << data->reference_point_id << '\n';
298  }
299  else if (auto data = try_instantiate<realsense_legacy_msgs::stream_info>(m))
300  {
301  os << "stream_type : " << data->stream_type << '\n';
302  os << "fps : " << data->fps << '\n';
303  os << "camera_info : " << data->camera_info << '\n';
304  os << "stream_extrinsics : " << data->stream_extrinsics << '\n';
305  os << "width : " << data->width << '\n';
306  os << "height : " << data->height << '\n';
307  os << "encoding : " << data->encoding << '\n';
308  }
309  else if (auto data = try_instantiate<realsense_legacy_msgs::vendor_data>(m))
310  {
311  os << "name : " << data->name << '\n';
312  os << "value : " << data->value << '\n';
313  }
314  else
315  {
316  os << m.getDataType() << '\n';
317  }
318 
319  return os;
320  }
321 
322 
323 }
const GLfloat * m
Definition: glext.h:6814
GLsizei const GLchar *const * string
d
Definition: rmse.py:171
GLuint GLuint stream
Definition: glext.h:1790
GLenum GLenum GLsizei void * image
GLuint GLfloat * val
Definition: parser.hpp:154
bool isType() const
Test whether the underlying message of the specified type.
static std::string accel
Definition: hid-types.h:24
const GLubyte * c
Definition: glext.h:12690
A class pointing into a bag file.
std::string value
Definition: parser.hpp:155
std::chrono::duration< uint64_t, std::nano > nanoseconds
tmpstringstream & operator<<(const T &val)
Definition: print_helpers.h:33
std::ostream & print_container(std::ostream &os, const Container &c)
Definition: print_helpers.h:60
std::string pretty_time(std::chrono::nanoseconds d)
Definition: print_helpers.h:37
std::string key
Definition: parser.hpp:155
ROS_TYPE::ConstPtr try_instantiate(const rosbag::MessageInstance &m)
Definition: print_helpers.h:96
std::string const & getDataType() const
int i
std::shared_ptr< T > instantiate() const
Templated call to instantiate a message.
GLboolean * data
GLdouble v
Definition: parser.hpp:150
::realsense_legacy_msgs::stream_info_< std::allocator< void > > stream_info
Definition: stream_info.h:79


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