From 106c253badfe7cc5a941d8106d0c12f5eaa4c77d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 12 Mar 2021 12:58:07 +0900 Subject: [PATCH] [sensor_msgs] add PanoramaInfo.msg and update CMakeLists.txt --- sensor_msgs/CMakeLists.txt | 1 + sensor_msgs/msg/PanoramaInfo.msg | 32 ++++++++++++++++++++++++++++++++ 2 files changed, 33 insertions(+) create mode 100644 sensor_msgs/msg/PanoramaInfo.msg diff --git a/sensor_msgs/CMakeLists.txt b/sensor_msgs/CMakeLists.txt index 3a8cfbc8..581ba203 100644 --- a/sensor_msgs/CMakeLists.txt +++ b/sensor_msgs/CMakeLists.txt @@ -30,6 +30,7 @@ add_message_files( MultiEchoLaserScan.msg NavSatFix.msg NavSatStatus.msg + PanoramaInfo.msg PointCloud.msg PointCloud2.msg PointField.msg diff --git a/sensor_msgs/msg/PanoramaInfo.msg b/sensor_msgs/msg/PanoramaInfo.msg new file mode 100644 index 00000000..3258f520 --- /dev/null +++ b/sensor_msgs/msg/PanoramaInfo.msg @@ -0,0 +1,32 @@ +# This message defines meta information for a panorama image. It should +# be in the same namespace with a image topic. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, panorama image coordinate frame ID +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be frame of panorama image + # origin of frame should be projection center + # +x should point to the front of a sphere + # +z should point to the top of a sphere + +####################################################################### +# Image projection info # +####################################################################### + +# The projection model from spherical view to a flat image. +# E.g. "Equirectangular" +string projection_model + +####################################################################### +# Field of View Parameters # +####################################################################### + +# Specifying field of view of a panorama image. +# theta, phi are azimuthal and polar angle of spherical coordinate. +float64 theta_min +float64 theta_max +float64 phi_min +float64 phi_max