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" 32 std::ostringstream
ss;
39 auto hhh = std::chrono::duration_cast<std::chrono::hours>(
d);
41 auto mm = std::chrono::duration_cast<std::chrono::minutes>(
d);
43 auto ss = std::chrono::duration_cast<std::chrono::seconds>(
d);
45 auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(
d);
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();
59 template <
typename Container>
62 for (
size_t i = 0;
i < c.size(); ++
i)
71 template <
size_t N,
typename T>
72 std::ostream& operator<<(std::ostream& os, const std::array<T, N>& arr)
78 std::ostream& operator<<(std::ostream& os, const std::vector<T>&
v)
95 template <
typename ROS_TYPE>
105 if (
auto data = try_instantiate<std_msgs::UInt32>(m))
107 os <<
"Value : " <<
data->data << std::endl;
109 else if (
auto data = try_instantiate<std_msgs::String>(m))
111 os <<
"Value : " <<
data->data << std::endl;
113 else if (
auto data = try_instantiate<std_msgs::Float32>(m))
115 os <<
"Value : " <<
data->data << std::endl;
117 else if (
auto data = try_instantiate<diagnostic_msgs::KeyValue>(m))
120 os <<
"Key : " <<
kvp->
key << std::endl;
121 os <<
"Value : " <<
kvp->
value << std::endl;
123 else if (
auto data = try_instantiate<realsense_msgs::StreamInfo>(m))
126 os <<
"Encoding : " <<
stream_info->encoding << std::endl;
128 os <<
"Is Recommended : " << (
stream_info->is_recommended ?
"True" :
"False") << std::endl;
130 else if (
auto data = try_instantiate<sensor_msgs::CameraInfo>(m))
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;
146 else if (
auto data = try_instantiate<realsense_msgs::ImuIntrinsic>(m))
148 os <<
"bias_variances : " <<
data->bias_variances <<
'\n';
149 os <<
"data : " <<
data->data <<
'\n';
150 os <<
"noise_variances : " <<
data->noise_variances <<
'\n';
152 else if (
auto data = try_instantiate<sensor_msgs::Image>(m))
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;
166 else if (
auto data = try_instantiate<sensor_msgs::Imu>(m))
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';
180 else if (
auto data = try_instantiate<sensor_msgs::TimeReference>(m))
183 os <<
" Header : " << tr->header << std::endl;
184 os <<
" Source : " << tr->source << std::endl;
185 os <<
" TimeReference : " << tr->time_ref << std::endl;
187 else if (
auto data = try_instantiate<geometry_msgs::Transform>(m))
190 os <<
" Rotation : " << tf->rotation << std::endl;
191 os <<
" Translation : " << tf->translation << std::endl;
193 else if (try_instantiate<geometry_msgs::Twist>(m) || try_instantiate<geometry_msgs::Accel>(
m))
195 if (m.
getDataType().find(
"Twist") != std::string::npos)
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;
201 if (m.
getDataType().find(
"Accel") != std::string::npos)
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;
215 else if (
auto data = try_instantiate<realsense_legacy_msgs::compressed_frame_info>(m))
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';
225 else if (
auto data = try_instantiate<realsense_legacy_msgs::controller_command>(m))
227 os <<
"controller_id : " <<
data->controller_id <<
'\n';
228 os <<
"mac_address : " <<
data->mac_address <<
'\n';
229 os <<
"type : " <<
data->type <<
'\n';
231 else if (
auto data = try_instantiate<realsense_legacy_msgs::controller_event>(m))
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';
238 else if (
auto data = try_instantiate<realsense_legacy_msgs::controller_vendor_data>(m))
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';
246 else if (
auto data = try_instantiate<realsense_legacy_msgs::extrinsics>(m))
248 os <<
" Extrinsics : " << std::endl;
249 os <<
" Rotation : " <<
data->rotation << std::endl;
250 os <<
" Translation : " <<
data->translation << std::endl;
252 else if (
auto data = try_instantiate<realsense_legacy_msgs::frame_info>(m))
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';
258 else if (
auto data = try_instantiate<realsense_legacy_msgs::metadata>(m))
260 os <<
"type : " <<
data->type <<
'\n';
261 os <<
"data : " <<
data->data <<
'\n';
263 else if (
auto data = try_instantiate<realsense_legacy_msgs::motion_intrinsics>(m))
265 os <<
"bias_variances : " <<
data->bias_variances <<
'\n';
266 os <<
"data : " <<
data->data <<
'\n';
267 os <<
"noise_variances : " <<
data->noise_variances <<
'\n';
269 else if (
auto data = try_instantiate<realsense_legacy_msgs::motion_stream_info>(m))
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';
276 else if (
auto data = try_instantiate<realsense_legacy_msgs::occupancy_map>(m))
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';
283 else if (
auto data = try_instantiate<realsense_legacy_msgs::pose>(m))
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';
294 else if (
auto data = try_instantiate<realsense_legacy_msgs::stream_extrinsics>(m))
296 os <<
"extrinsics : " <<
data->extrinsics <<
'\n';
297 os <<
"reference_point_id : " <<
data->reference_point_id <<
'\n';
299 else if (
auto data = try_instantiate<realsense_legacy_msgs::stream_info>(m))
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';
309 else if (
auto data = try_instantiate<realsense_legacy_msgs::vendor_data>(m))
311 os <<
"name : " <<
data->name <<
'\n';
312 os <<
"value : " <<
data->value <<
'\n';
GLsizei const GLchar *const * string
GLenum GLenum GLsizei void * image
bool isType() const
Test whether the underlying message of the specified type.
A class pointing into a bag file.
std::chrono::duration< uint64_t, std::nano > nanoseconds
tmpstringstream & operator<<(const T &val)
std::ostream & print_container(std::ostream &os, const Container &c)
std::string pretty_time(std::chrono::nanoseconds d)
ROS_TYPE::ConstPtr try_instantiate(const rosbag::MessageInstance &m)
std::string const & getDataType() const
std::shared_ptr< T > instantiate() const
Templated call to instantiate a message.
::realsense_legacy_msgs::stream_info_< std::allocator< void > > stream_info