Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Image/PointCloud Snapshot as a service #105

Open
wants to merge 7 commits into
base: jade-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 12 additions & 3 deletions sensor_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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()
Expand Down Expand Up @@ -41,9 +41,18 @@ add_message_files(

add_service_files(
DIRECTORY srv
FILES SetCameraInfo.srv)
FILES
SetCameraInfo.srv
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
Expand Down
22 changes: 22 additions & 0 deletions sensor_msgs/action/AdvancedSnapshotCloud.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
# dense_cloud = true, if the cloud has to be dense (ordered)
bool dense_cloud

# exposure in milliseconds (0 indicates autoexposure)
uint32 exposure

uint8 raw_data
uint8 NO_RAW_DATA = 0
uint8 GRAYSCALE = 1
uint8 RGB = 2

---

# 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
2 changes: 2 additions & 0 deletions sensor_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,12 @@
<build_depend>geometry_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>actionlib_msgs</build_depend>

<run_depend>geometry_msgs</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>actionlib_msgs</run_depend>

<export>
<architecture_independent/>
Expand Down
17 changes: 17 additions & 0 deletions sensor_msgs/srv/SnapshotCloud.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# Point Cloud as a service

# REQUEST:

# dense_cloud = true, if the cloud has to be dense (ordered)
bool dense_cloud

# exposure in milliseconds (0 indicates autoexposure)
uint32 exposure
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you really expect to be setting the exposure time for a cloud? This seems to be breaking several abstractions that you must know about the sensor's parameters and lighting situation to request a snapshot?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you mean to let the exposure config through another mechanism like, for instance, dynamic reconfigure, so keep the request even more simple ?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes. This standalone argument means nothing unless you know a lot more about the system. It has implications for side effects too, such as will this modify the system if it's already running with the exposure setting? What does the exposure setting mean if this snapshot is implemented with a data source such as a laser?


---

# RESPONSE:

# cloud is the returning point cloud
sensor_msgs/PointCloud2 cloud

17 changes: 17 additions & 0 deletions sensor_msgs/srv/SnapshotImage.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# Image as a service

# REQUEST

# exposure in milliseconds (0 indicates autoexposure)
uint32 exposure
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There's the same issue here. Unless you're going to provide all the settings providing just one doesn't make much sense.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, I agree. Providing one parameter is quite arbitrary and not general. I can modify both srv with an std_msgs/Empty in the request side.
Another possibility could be to request with an std_msgs/UInt8 indicating the number of snapshots to take, and reply with a vector of either sensor_msgs/PointCloud2 or sensor_msgs/Image.
By the way, thanks for reviewing this PR!


---

# RESPONSE:

# image is the returning raw image
sensor_msgs/Image image

# camera info, which includes intrinsics calibration
sensor_msgs/CameraInfo camera_info