Skip to content

Commit

Permalink
document remaining nodes
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Feb 5, 2024
1 parent 1e08483 commit 618b55a
Show file tree
Hide file tree
Showing 2 changed files with 111 additions and 20 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
*pyc
.vscode/settings.json
*/doc/generated
130 changes: 110 additions & 20 deletions depth_image_proc/doc/components.rst
Original file line number Diff line number Diff line change
Expand Up @@ -9,30 +9,50 @@ Alternatively, each component can be run as a standalone node.

depth_image_proc::ConvertMetricNode
-----------------------------------
Component to convert raw uint16 depth image in mm to float depth image in m.
Component to convert raw uint16 depth image in millimeters to
float depth image in meters.
Also available as a standalone node with the name ``convert_metric_node``.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **image_raw** (sensor_msgs/Image): ``uint16`` depth image in mm, the native
OpenNI format.
* **image_raw** (sensor_msgs/Image): ``uint16`` depth image in millimeters,
the native OpenNI format.

Published Topics
^^^^^^^^^^^^^^^^
* **image** (sensor_msgs/Image): ``float`` depth image in m, the recommended
format for processing in ROS.
* **image** (sensor_msgs/Image): ``float`` depth image in meters, the
recommended format for processing in ROS 2.

Parameters
^^^^^^^^^^
* **image_transport** (string, default: raw): Image transport to use.

depth_image_proc::CropForemostNode
----------------------------------
TODO
Takes a depth image and crops the closest element. The node will find the
minimum depth value in the image and then set all pixels farther than
``min + distance`` to 0. Also available as a standalone node
``crop_foremost_node``.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **image_raw** (sensor_msgs/Image): Must be a depth (single channel) image.

Published Topics
^^^^^^^^^^^^^^^^
* **image** (sensor_msgs/Image): Cropped image.

Parameters
^^^^^^^^^^
* **distance** (float, default: 0.0): The depth tolerance to use when
thresholding the image. Pixels farther than ``min + distance`` will be
set to 0.
* **image_transport** (string, default: raw): Image transport to use.

depth_image_proc::DisparityNode
-------------------------------
Comoonent to convert depth image to disparity image.
Converts a depth image to disparity image. Also available as a standalone
node ``disparity_node``.

TODO: copy images in here

Expand Down Expand Up @@ -61,14 +81,14 @@ Parameters

depth_image_proc::PointCloudXyzNode
-----------------------------------
Component to convert depth image to XYZ point cloud.
Converts a depth image to XYZ point cloud. Also available as a standalone
node ``point_cloud_xyz_node``.

TODO: copy images

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **depth/image_rect** (sensor_msgs/Image): Rectified depth image.
* **intensity/image_rect** (sensor_msgs/Image): Rectified intensity image.
* **image_rect** (sensor_msgs/Image): Rectified depth image.
* **camera_info** (sensor_msgs/CameraInfo): Camera calibration and metadata.

Published Topics
Expand All @@ -80,23 +100,43 @@ Parameters
^^^^^^^^^^
* **depth_image_transport** (string, default: raw): Image transport to use
for the depth topic subscriber.
* **image_transport** (string, default: raw): Image transport to use for
the intensity image subscriber.
* **queue_size** (int, default: 5): Size of message queue for synchronizing
subscribed topics.

depth_image_proc::PointCloudXyzRadialNode
-----------------------------------------
TODO
Converts a radial depth image to an XYZ point cloud. Note that radial nodes
assume an unrectified radial image, and therefore use the K and D matrices
of the camera info message, rather than the P matrix. Also available as a
standalone node ``point_cloud_xyz_radial_node``.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **depth/image_raw** (sensor_msgs/Image): Unrectified radial depth image.
* **depth/camera_info** (sensor_msgs/CameraInfo): Camera calibration and metadata.

Published Topics
^^^^^^^^^^^^^^^^
* **points** (sensor_msgs/PointCloud2): XYZ point cloud. If using PCL,
subscribe as PointCloud<PointXYZ>.

Parameters
^^^^^^^^^^
* **depth_image_transport** (string, default: raw): Image transport to use
for the depth topic subscriber.
* **queue_size** (int, default: 5): Size of message queue for synchronizing
subscribed topics.

depth_image_proc::PointCloudXyziNode
------------------------------------
Component to convert depth image to XYZI point cloud.
Component to convert depth image to XYZI point cloud. Also available as a
standalone node ``point_cloud_xyzi_node``.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **image_rect** (sensor_msgs/Image): Rectified depth image.
* **camera_info** (sensor_msgs/CameraInfo): Camera calibration and metadata.
* **depth/image_rect** (sensor_msgs/Image): Rectified depth image.
* **intensity/image_rect** (sensor_msgs/Image): Rectified intensity image.
* **intensity/camera_info** (sensor_msgs/CameraInfo): Camera calibration and metadata.

Published Topics
^^^^^^^^^^^^^^^^
Expand All @@ -105,17 +145,44 @@ Published Topics

Parameters
^^^^^^^^^^
* **depth_image_transport** (string, default: raw): Image transport to use.
* **depth_image_transport** (string, default: raw): Image transport to use
for the depth topic subscriber.
* **image_transport** (string, default: raw): Image transport to use for
the intensity image subscriber.
* **queue_size** (int, default: 5): Size of message queue for synchronizing
subscribed topics.

depth_image_proc::PointCloudXyziRadialNode
------------------------------------------
TODO
Converts a radial depth image and an intensity image to an XYZI point cloud.
Note that radial nodes assume an unrectified radial image, and therefore
use the K and D matrices of the camera info message, rather than the P matrix.
Also available as a standalone node ``point_cloud_xyzi_radial_node``.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **depth/image_raw** (sensor_msgs/Image): Unrectified radial depth image.
* **intensity/image_raw** (sensor_msgs/Image): Unrectified intensity image.
* **intensity/camera_info** (sensor_msgs/CameraInfo): Camera calibration and metadata.

Published Topics
^^^^^^^^^^^^^^^^
* **points** (sensor_msgs/PointCloud2): XYZI point cloud. If using PCL,
subscribe as PointCloud<PointXYZI>.

Parameters
^^^^^^^^^^
* **depth_image_transport** (string, default: raw): Image transport to use
for the depth topic subscriber.
* **image_transport** (string, default: raw): Image transport to use for
the intensity image subscriber.
* **queue_size** (int, default: 5): Size of message queue for synchronizing
subscribed topics.

depth_image_proc::PointCloudXyzrgbNode
--------------------------------------
Component combine registered depth image and RGB image into XYZRGB point cloud.
Combines a registered depth image and an RGB image into XYZRGB point cloud.
Also available as a standalone node ``point_cloud_xyzrgb_node``.

TODO: copy images

Expand Down Expand Up @@ -143,7 +210,30 @@ Parameters

depth_image_proc::PointCloudXyzrgbRadialNode
--------------------------------------------
TODO
Converts a radial depth image and an rgb image to an XYZRGB point cloud.
Note that radial nodes assume an unrectified radial image, and therefore
use the K and D matrices of the camera info message, rather than the P matrix.
Also available as a standalone node ``point_cloud_xyzrgb_radial_node``.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **depth/image_raw** (sensor_msgs/Image): Unrectified radial depth image.
* **rgb/image_raw** (sensor_msgs/Image): Unrectified rgb image.
* **rgb/camera_info** (sensor_msgs/CameraInfo): Camera calibration and metadata.

Published Topics
^^^^^^^^^^^^^^^^
* **points** (sensor_msgs/PointCloud2): XYZRGB point cloud. If using PCL,
subscribe as PointCloud<PointXYZRGB>.

Parameters
^^^^^^^^^^
* **depth_image_transport** (string, default: raw): Image transport to use
for the depth topic subscriber.
* **image_transport** (string, default: raw): Image transport to use for
the rgb image subscriber.
* **queue_size** (int, default: 5): Size of message queue for synchronizing
subscribed topics.

depth_image_proc::RegisterNode
------------------------------
Expand Down

0 comments on commit 618b55a

Please sign in to comment.