// License: Apache 2.0. See LICENSE file in root directory. // Copyright(c) 2017 Intel Corporation. All Rights Reserved. #pragma once #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include namespace rosbag_inspector { struct tmpstringstream { std::ostringstream ss; template tmpstringstream & operator << (const T & val) { ss << val; return *this; } operator std::string() const { return ss.str(); } }; inline std::string pretty_time(std::chrono::nanoseconds d) { auto hhh = std::chrono::duration_cast(d); d -= hhh; auto mm = std::chrono::duration_cast(d); d -= mm; auto ss = std::chrono::duration_cast(d); d -= ss; auto ms = std::chrono::duration_cast(d); std::ostringstream stream; stream << std::setfill('0') << std::setw(3) << hhh.count() << ':' << std::setfill('0') << std::setw(2) << mm.count() << ':' << std::setfill('0') << std::setw(2) << ss.count() << '.' << std::setfill('0') << std::setw(3) << ms.count(); return stream.str(); } // Streamers template std::ostream& print_container(std::ostream& os, const Container& c) { for (size_t i = 0; i < c.size(); ++i) { if (i != 0) os << ","; os << c[i]; } return os; } template std::ostream& operator<<(std::ostream& os, const std::array& arr) { return print_container(os, arr); } template std::ostream& operator<<(std::ostream& os, const std::vector& v) { return print_container(os, v); } std::ostream& operator<<(std::ostream& os, rosbag::compression::CompressionType c) { switch (c) { case rosbag::CompressionType::Uncompressed: os << "Uncompressed"; break; case rosbag::CompressionType::BZ2: os << "BZ2"; break; case rosbag::CompressionType::LZ4: os << "LZ4"; break; default: break; } return os; } template inline typename ROS_TYPE::ConstPtr try_instantiate(const rosbag::MessageInstance& m) { if(m.isType()) return m.instantiate(); return nullptr; } std::ostream& operator<<(std::ostream& os, const rosbag::MessageInstance& m) { if (auto data = try_instantiate(m)) { os << "Value : " << data->data << std::endl; } else if (auto data = try_instantiate(m)) { os << "Value : " << data->data << std::endl; } else if (auto data = try_instantiate(m)) { os << "Value : " << data->data << std::endl; } else if (auto data = try_instantiate(m)) { auto kvp = data; os << "Key : " << kvp->key << std::endl; os << "Value : " << kvp->value << std::endl; } else if (auto data = try_instantiate(m)) { auto stream_info = data; os << "Encoding : " << stream_info->encoding << std::endl; os << "FPS : " << stream_info->fps << std::endl; os << "Is Recommended : " << (stream_info->is_recommended ? "True" : "False") << std::endl; } else if (auto data = try_instantiate(m)) { auto camera_info = data; os << "Width : " << camera_info->width << std::endl; os << "Height : " << camera_info->height << std::endl; os << "Intrinsics : " << std::endl; os << " Focal Point : " << camera_info->K[0] << ", " << camera_info->K[4] << std::endl; os << " Principal Point : " << camera_info->K[2] << ", " << camera_info->K[5] << std::endl; os << " Coefficients : " << camera_info->D[0] << ", " << camera_info->D[1] << ", " << camera_info->D[2] << ", " << camera_info->D[3] << ", " << camera_info->D[4] << std::endl; os << " Distortion Model : " << camera_info->distortion_model << std::endl; } else if (auto data = try_instantiate(m)) { os << "bias_variances : " << data->bias_variances << '\n'; os << "data : " << data->data << '\n'; os << "noise_variances : " << data->noise_variances << '\n'; } else if (auto data = try_instantiate(m)) { auto image = data; os << "Header : \n"; os << " frame_id : " << image->header.version << std::endl; os << " Frame Number (seq) : " << image->header.seq << std::endl; os << " stamp : " << image->header.stamp << std::endl; os << "Encoding : " << image->encoding << std::endl; os << "Width : " << image->width << std::endl; os << "Height : " << image->height << std::endl; os << "Step : " << image->step << std::endl; } else if (auto data = try_instantiate(m)) { auto imu = data; os << "header : " << imu->header << '\n'; os << "orientation : " << imu->orientation << '\n'; os << "orientation_covariance : " << imu->orientation_covariance << '\n'; os << "angular_velocity : " << imu->angular_velocity << '\n'; os << "angular_velocity_covariance : " << imu->angular_velocity_covariance << '\n'; os << "linear_acceleration : " << imu->linear_acceleration << '\n'; os << "linear_acceleration_covariance : " << imu->linear_acceleration_covariance << '\n'; os << "orientation_covariance : " << imu->orientation_covariance << '\n'; os << "angular_velocity_covariance : " << imu->angular_velocity_covariance << '\n'; os << "linear_acceleration_covariance : " << imu->linear_acceleration_covariance << '\n'; } else if (auto data = try_instantiate(m)) { auto tr = data; os << " Header : " << tr->header << std::endl; os << " Source : " << tr->source << std::endl; os << " TimeReference : " << tr->time_ref << std::endl; } else if (auto data = try_instantiate(m)) { auto tf = data; os << " Rotation : " << tf->rotation << std::endl; os << " Translation : " << tf->translation << std::endl; } else if (try_instantiate(m) || try_instantiate(m)) { if (m.getDataType().find("Twist") != std::string::npos) { auto twist = try_instantiate(m); os << "Angular Velocity: " << twist->angular << std::endl; os << "Linear Velocity: " << twist->linear << std::endl; } if (m.getDataType().find("Accel") != std::string::npos) { auto accel = try_instantiate(m); os << "Angular Acceleration: " << accel->angular << std::endl; os << "Linear Acceleration: " << accel->linear << std::endl; } } /*************************************************************/ /*************************************************************/ /* Legacy Messages */ /*************************************************************/ /*************************************************************/ else if (auto data = try_instantiate(m)) { os << "encoding: " << data->encoding << '\n'; os << "frame_metadata: " << data->frame_metadata << '\n'; os << "height: " << data->height << '\n'; os << "step: " << data->step << '\n'; os << "system_time: " << data->system_time << '\n'; os << "time_stamp_domain: " << data->time_stamp_domain << '\n'; os << "width: " << data->width << '\n'; } else if (auto data = try_instantiate(m)) { os << "controller_id : " << data->controller_id << '\n'; os << "mac_address : " << data->mac_address << '\n'; os << "type : " << data->type << '\n'; } else if (auto data = try_instantiate(m)) { os << "controller_id : " << data->controller_id << '\n'; os << "mac_address : " << data->mac_address << '\n'; os << "type : " << data->type << '\n'; os << "timestamp : " << data->timestamp << '\n'; } else if (auto data = try_instantiate(m)) { os << "controller_id : " << data->controller_id << '\n'; os << "data : " << data->data << '\n'; os << "timestamp : " << data->timestamp << '\n'; os << "vendor_data_source_index : " << data->vendor_data_source_index << '\n'; os << "vendor_data_source_type : " << data->vendor_data_source_type << '\n'; } else if (auto data = try_instantiate(m)) { os << " Extrinsics : " << std::endl; os << " Rotation : " << data->rotation << std::endl; os << " Translation : " << data->translation << std::endl; } else if (auto data = try_instantiate(m)) { os << "frame_metadata :" << data->frame_metadata << '\n'; os << "system_time :" << data->system_time << '\n'; os << "time_stamp_domain :" << data->time_stamp_domain << '\n'; } else if (auto data = try_instantiate(m)) { os << "type : " << data->type << '\n'; os << "data : " << data->data << '\n'; } else if (auto data = try_instantiate(m)) { os << "bias_variances : " << data->bias_variances << '\n'; os << "data : " << data->data << '\n'; os << "noise_variances : " << data->noise_variances << '\n'; } else if (auto data = try_instantiate(m)) { os << "fps : " << data->fps << '\n'; os << "motion_type : " << data->motion_type << '\n'; os << "stream_extrinsics : " << data->stream_extrinsics << '\n'; os << "stream_intrinsics : " << data->stream_intrinsics << '\n'; } else if (auto data = try_instantiate(m)) { os << "accuracy : " << data->accuracy << '\n'; os << "reserved : " << data->reserved << '\n'; os << "tiles : " << data->tiles << '\n'; os << "tile_count : " << data->tile_count << '\n'; } else if (auto data = try_instantiate(m)) { os << "translation : " << data->translation << '\n'; os << "rotation : " << data->rotation << '\n'; os << "velocity : " << data->velocity << '\n'; os << "angular_velocity : " << data->angular_velocity << '\n'; os << "acceleration : " << data->acceleration << '\n'; os << "angular_acceleration : " << data->angular_acceleration << '\n'; os << "timestamp : " << data->timestamp << '\n'; os << "system_timestamp : " << data->system_timestamp << '\n'; } else if (auto data = try_instantiate(m)) { os << "extrinsics : " << data->extrinsics << '\n'; os << "reference_point_id : " << data->reference_point_id << '\n'; } else if (auto data = try_instantiate(m)) { os << "stream_type : " << data->stream_type << '\n'; os << "fps : " << data->fps << '\n'; os << "camera_info : " << data->camera_info << '\n'; os << "stream_extrinsics : " << data->stream_extrinsics << '\n'; os << "width : " << data->width << '\n'; os << "height : " << data->height << '\n'; os << "encoding : " << data->encoding << '\n'; } else if (auto data = try_instantiate(m)) { os << "name : " << data->name << '\n'; os << "value : " << data->value << '\n'; } else { os << m.getDataType() << '\n'; } return os; } }