Skip to content

Commit

Permalink
add docs
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Dec 6, 2024
1 parent c5787d9 commit 1aa182d
Show file tree
Hide file tree
Showing 2 changed files with 31 additions and 3 deletions.
30 changes: 30 additions & 0 deletions image_rotate/doc/components.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,36 @@
Nodes and Components
====================

image_rotate::ImageFlipNode
-----------------------------
This is a simplified version image rotate which merely rotates/flips
the images.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **image** (sensor_msgs/Image): Image to be rotated.
* **camera_info** (sensor_msgs/CameraInfo): Camera metadata, only
used if ``use_camera_info`` is set to true.

Published Topics
^^^^^^^^^^^^^^^^
* **rotated/image** (sensor_msgs/Image): Rotated image.
* **out/camera_info** (sensor_msgs/CameraInfo): Camera metadata, with binning and
ROI fields adjusted to match output raw image.

Parameters
^^^^^^^^^^
* **output_frame_id** (str, default: ""): Frame to publish for the image's
new orientation. Empty means add '_rotated' suffix to the image frame.
* **use_camera_info** (bool, default: True): Indicates that the camera_info
topic should be subscribed to to get the default input_frame_id.
Otherwise the frame from the image message will be used.
* **rotation_steps** (int, default: 2): Number of times to rotate the image:

* 1 is transpose and flip in CCW
* 2 is flip (180 mirroring)
* 3 is transpose and flip in CW

image_rotate::ImageRotateNode
-----------------------------
Node to rotate an image for visualization. The node takes a source
Expand Down
4 changes: 1 addition & 3 deletions image_rotate/launch/image_flip.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,4 @@ def generate_launch_description():
('rotated/image', 'camera_rotated/image_rotated')],
parameters=[{'output_frame_id': 'camera_rotated',
'rotation_steps': 2,
'use_camera_info': True,
'input_qos': 'best_effort',
'output_qos': 'default'}])])
'use_camera_info': True}])])

0 comments on commit 1aa182d

Please sign in to comment.