From 62b378aa8721099dc0221b3cccb91b8c2baa8918 Mon Sep 17 00:00:00 2001 From: andreucm Date: Thu, 13 Apr 2017 19:50:33 +0200 Subject: [PATCH 1/6] Added SnapshotCloud service, to implement point cloud capture as a service. --- sensor_msgs/srv/SnapshotCloud.srv | 14 ++++++++++++++ 1 file changed, 14 insertions(+) create mode 100644 sensor_msgs/srv/SnapshotCloud.srv diff --git a/sensor_msgs/srv/SnapshotCloud.srv b/sensor_msgs/srv/SnapshotCloud.srv new file mode 100644 index 00000000..5a355dd9 --- /dev/null +++ b/sensor_msgs/srv/SnapshotCloud.srv @@ -0,0 +1,14 @@ +#Request/Reply for Point Cloud as a service + +# Request: +# dense_cloud = true if the cloud has to be dense (ordered) +# exposure in milliseconds (0 indicates autoexposure) +bool dense_cloud +uint32 exposure + +--- + +# Reply: +# cloud is the returning point cloud +sensor_msgs/PointCloud2 cloud + From 72fcbee701ff91d9f71b47c85be9869341197ab4 Mon Sep 17 00:00:00 2001 From: andreucm Date: Thu, 13 Apr 2017 20:22:52 +0200 Subject: [PATCH 2/6] Added SnapshotCloud.srv at CMakeLists --- sensor_msgs/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/sensor_msgs/CMakeLists.txt b/sensor_msgs/CMakeLists.txt index 06076c48..8bde4685 100644 --- a/sensor_msgs/CMakeLists.txt +++ b/sensor_msgs/CMakeLists.txt @@ -41,7 +41,9 @@ add_message_files( add_service_files( DIRECTORY srv - FILES SetCameraInfo.srv) + FILES + SetCameraInfo.srv + SnapshotCloud.srv) generate_messages(DEPENDENCIES geometry_msgs std_msgs) From f2f302b7f32fbc41339dfd7a87213d224855c83e Mon Sep 17 00:00:00 2001 From: andreucm Date: Fri, 21 Apr 2017 09:39:37 +0200 Subject: [PATCH 3/6] Added SnapshotImage service, implementing image as a service. Response both, the image and camera info. CMakeLists modified accordingly --- sensor_msgs/CMakeLists.txt | 3 ++- sensor_msgs/srv/SnapshotImage.srv | 17 +++++++++++++++++ 2 files changed, 19 insertions(+), 1 deletion(-) create mode 100644 sensor_msgs/srv/SnapshotImage.srv diff --git a/sensor_msgs/CMakeLists.txt b/sensor_msgs/CMakeLists.txt index 8bde4685..2a81aeb9 100644 --- a/sensor_msgs/CMakeLists.txt +++ b/sensor_msgs/CMakeLists.txt @@ -43,7 +43,8 @@ add_service_files( DIRECTORY srv FILES SetCameraInfo.srv - SnapshotCloud.srv) + SnapshotCloud.srv + SnapshotImage.srv) generate_messages(DEPENDENCIES geometry_msgs std_msgs) diff --git a/sensor_msgs/srv/SnapshotImage.srv b/sensor_msgs/srv/SnapshotImage.srv new file mode 100644 index 00000000..d9cad1d4 --- /dev/null +++ b/sensor_msgs/srv/SnapshotImage.srv @@ -0,0 +1,17 @@ +# Image as a service + +# REQUEST + +# exposure in milliseconds (0 indicates autoexposure) +uint32 exposure + +--- + +# RESPONSE: + +# image is the returning raw image +sensor_msgs/Image image + +# camera info, which includes intrinsics calibration +sensor_msgs/CameraInfo camera_info + From aacfcfc846f2b510c73aa5287b3f38cec147d2c0 Mon Sep 17 00:00:00 2001 From: andreucm Date: Fri, 21 Apr 2017 09:41:19 +0200 Subject: [PATCH 4/6] Improved comment lines of the service --- sensor_msgs/srv/SnapshotCloud.srv | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/sensor_msgs/srv/SnapshotCloud.srv b/sensor_msgs/srv/SnapshotCloud.srv index 5a355dd9..d823a2e9 100644 --- a/sensor_msgs/srv/SnapshotCloud.srv +++ b/sensor_msgs/srv/SnapshotCloud.srv @@ -1,14 +1,17 @@ -#Request/Reply for Point Cloud as a service +# Point Cloud as a service -# Request: -# dense_cloud = true if the cloud has to be dense (ordered) -# exposure in milliseconds (0 indicates autoexposure) +# REQUEST: + +# dense_cloud = true, if the cloud has to be dense (ordered) bool dense_cloud + +# exposure in milliseconds (0 indicates autoexposure) uint32 exposure --- -# Reply: -# cloud is the returning point cloud +# RESPONSE: + +# cloud is the returning point cloud sensor_msgs/PointCloud2 cloud From 9236c56b1d1c4f5115e0c312451c514ee531d015 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Rodoreda=20=C2=B7=20ESTEL?= Date: Thu, 11 Jul 2019 13:13:52 +0200 Subject: [PATCH 5/6] Add advancedSnapshot action with its dependencies in cmakelists and package.xml --- sensor_msgs/CMakeLists.txt | 10 ++++++++-- .../action/AdvancedSnapshotCloud.action | 19 +++++++++++++++++++ sensor_msgs/package.xml | 2 ++ 3 files changed, 29 insertions(+), 2 deletions(-) create mode 100644 sensor_msgs/action/AdvancedSnapshotCloud.action diff --git a/sensor_msgs/CMakeLists.txt b/sensor_msgs/CMakeLists.txt index 2a81aeb9..9df8a4c3 100644 --- a/sensor_msgs/CMakeLists.txt +++ b/sensor_msgs/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(sensor_msgs) -find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) +find_package(catkin REQUIRED COMPONENTS geometry_msgs actionlib_msgs message_generation std_msgs) # For point_cloud2.py catkin_python_setup() @@ -46,7 +46,13 @@ add_service_files( SnapshotCloud.srv SnapshotImage.srv) -generate_messages(DEPENDENCIES geometry_msgs std_msgs) +add_action_files( + DIRECTORY action + FILES + AdvancedSnapshotCloud.action +) + +generate_messages(DEPENDENCIES geometry_msgs std_msgs actionlib_msgs) catkin_package( INCLUDE_DIRS include diff --git a/sensor_msgs/action/AdvancedSnapshotCloud.action b/sensor_msgs/action/AdvancedSnapshotCloud.action new file mode 100644 index 00000000..315ebb40 --- /dev/null +++ b/sensor_msgs/action/AdvancedSnapshotCloud.action @@ -0,0 +1,19 @@ +# dense_cloud = true, if the cloud has to be dense (ordered) +bool dense_cloud + +# exposure in milliseconds (0 indicates autoexposure) +uint32 exposure + +bool raw_data + +--- + +# cloud is the returning point cloud +sensor_msgs/PointCloud2 cloud + +# image is the 2d data form the camera +sensor_msgs/Image image + +--- + +uint32 percentage_completed diff --git a/sensor_msgs/package.xml b/sensor_msgs/package.xml index 7f273282..eeb49360 100644 --- a/sensor_msgs/package.xml +++ b/sensor_msgs/package.xml @@ -15,10 +15,12 @@ geometry_msgs message_generation std_msgs + actionlib_msgs geometry_msgs message_runtime std_msgs + actionlib_msgs From f115ce8695080e2badbf22b6cd71c3b610e9a907 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Rodoreda=20=C2=B7=20ESTEL?= Date: Thu, 11 Jul 2019 15:50:57 +0200 Subject: [PATCH 6/6] Add rgb in advanced snapshot --- sensor_msgs/action/AdvancedSnapshotCloud.action | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/sensor_msgs/action/AdvancedSnapshotCloud.action b/sensor_msgs/action/AdvancedSnapshotCloud.action index 315ebb40..c193c8da 100644 --- a/sensor_msgs/action/AdvancedSnapshotCloud.action +++ b/sensor_msgs/action/AdvancedSnapshotCloud.action @@ -4,7 +4,10 @@ bool dense_cloud # exposure in milliseconds (0 indicates autoexposure) uint32 exposure -bool raw_data +uint8 raw_data +uint8 NO_RAW_DATA = 0 +uint8 GRAYSCALE = 1 +uint8 RGB = 2 ---