Skip to content

Commit

Permalink
Adapt ceiling cam package to camera driver
Browse files Browse the repository at this point in the history
  • Loading branch information
Flova committed Mar 27, 2024
1 parent a1ca024 commit c9f8dbb
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 130 deletions.
131 changes: 18 additions & 113 deletions bitbots_misc/bitbots_ceiling_cam/config/camera_settings_ceiling_cam.yaml
Original file line number Diff line number Diff line change
@@ -1,123 +1,28 @@

/**:
/ceiling_cam_publisher:
ros__parameters:

# The tf frame under which the images were published
camera_frame: ceiling_cam

# The DeviceUserID of the camera. If empty, the first camera found in the
# device list will be used
# device_user_id: ""
# The tf frame under which the images were published
camera_frame_id: ceiling_cam

# The CameraInfo URL (Uniform Resource Locator) where the optional intrinsic
# camera calibration parameters are stored. This URL string will be parsed
# from the ROS-CameraInfoManager:
# http://docs.ros.org/api/camera_info_manager/html/classcamera__info__manager_
# 1_1CameraInfoManager.html#details
camera_info_url: "package://bitbots_ceiling_cam/config/camera_calibration_ceiling_cam.yaml"

# The encoding of the pixels -- channel meaning, ordering, size
# taken from the list of strings in include/sensor_msgs/image_encodings.h
# The supported encodings are 'mono8', 'bgr8', 'rgb8', 'bayer_bggr8',
# 'bayer_gbrg8' and 'bayer_rggb8'
# Default values are 'mono8' and 'rgb8'
image_encoding: "bayer_rggb8"
# The name of the camera (used to discover the camera). The name can be set in the pylon viewer.
device_user_id: ceiling_cam

# Binning factor to get downsampled images. It refers here to any camera
# setting which combines rectangular neighborhoods of pixels into larger
# "super-pixels." It reduces the resolution of the output image to
# (width / binning_x) x (height / binning_y).
# The default values binning_x = binning_y = 0 are considered the same
# as binning_x = binning_y = 1 (no subsampling).
# binning_x: 4
# binning_y: 4

# The desired publisher frame rate if listening to the topics.
# This parameter can only be set once at startup
# Calling the GrabImages-Action can result in a higher framerate
frame_rate: 20.0
# The CameraInfo URL (Uniform Resource Locator) where the optional intrinsic
# camera calibration parameters are stored. This URL string will be parsed
# from the ROS-CameraInfoManager:
# http://docs.ros.org/api/camera_info_manager/html/classcamera__info__manager_1_1CameraInfoManager.html#details
camera_info_url: "package://bitbots_ceiling_cam/config/camera_calibration_ceiling_cam.yaml"

# Mode of camera's shutter.
# The supported modes are "rolling", "global" and "global_reset"
# Default value is "" (empty) means default_shutter_mode
shutter_mode: "global"
# No subsampling is used for the ceiling camera
binning_factor_x: 1
binning_factor_y: 1

##########################################################################
######################## Image Intensity Settings ########################
##########################################################################
# The following settings do *NOT* have to be set. Each camera has default
# values which provide an automatic image adjustment resulting in valid
# images
##########################################################################
# The target frame rate
fps: 20.0

# The exposure time in microseconds to be set after opening the camera.
# The exposure time in microseconds
exposure: 8000.0

# The target gain in percent of the maximal value the camera supports
# For USB-Cameras, the gain is in dB, for GigE-Cameras it is given in so
# called 'device specific units'.
gain: 0.3

# Gamma correction of pixel intensity.
# Adjusts the brightness of the pixel values output by the camera's sensor
# to account for a non-linearity in the human perception of brightness or
# of the display system (such as CRT).
gamma: 1.0

# The average intensity value of the images. It depends the exposure time
# as well as the gain setting. If 'exposure' is provided, the interface will
# try to reach the desired brightness by only varying the gain. (What may
# often fail, because the range of possible exposure vaules is many
# times higher than the gain range). If 'gain' is provided, the interface will
# try to reach the desired brightness by only varying the exposure time. If
# gain AND exposure are given, it is not possible to reach the brightness,
# because both are assumed to be fix.
# brightness: 100

# Only relevant, if 'brightness' is set:
# The brightness_continuous flag controls the auto brightness function.
# If it is set to false, the brightness will only be reached once.
# Hence changing light conditions lead to changing brightness values.
# If it is set to true, the given brightness will be reached continuously,
# trying to adapt to changing light conditions. This is only possible for
# values in the possible auto range of the pylon API which is e.g. [50 - 205]
# for acA2500-14um and acA1920-40gm
# brightness_continuous: true

# Only relevant, if 'brightness' is set:
# If the camera should try to reach and / or keep the brightness, hence
# adapting to changing light conditions, at least one of the following flags
# must be set.
# If both are set, the interface will use the profile that tries to keep the
# gain at minimum to reduce white noise.
# The exposure_auto flag indicates, that the desired brightness will be
# reached by adapting the exposure time.
# The gain_auto flag indicates, that the desired brightness will be
# reached by adapting the gain.
# exposure_auto: true
# gain_auto: true

##########################################################################

# The timeout while searching the exposure which is connected to the
# desired brightness. For slow system this has to be increased.
# exposure_search_timeout: 5.0

# The exposure search can be limited with an upper bound. This is to prevent
# very high exposure times and resulting timeouts.
# A typical value for this upper bound is ~2000000us.
# auto_exposure_upper_limit: 2000000.0

# The MTU size. Only used for GigE cameras.
# To prevent lost frames configure the camera has to be configured
# with the MTU size the network card supports. A value greater 3000
# should be good (1500 for RaspberryPI)
# gige:
# gige/mtu_size: 9000

# Only used for GigE cameras.
# The inter-package delay in ticks to prevent lost frames.
# For most of GigE-Cameras, a value of 1000 is reasonable.
# For cameras used on a RaspberryPI this value should be set to 11772.
# gige:
# gige/inter_pkg_delay: 1000
# The target raw gain of the camera sensor (similar to ISO)
gain: 150
24 changes: 9 additions & 15 deletions bitbots_misc/bitbots_ceiling_cam/launch/ceiling_cam.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,29 +3,23 @@
<node pkg="tf2_ros" exec="static_transform_publisher" name="field_mount" args="--x -0.051 --y -0.113 --z 3.370 --qx -0.997 --qy -0.012 --qz 0.070 --qw 0.026 --frame-id ceiling_cam --child-frame-id field" />

<!-- camera driver -->
<include file="$(find-pkg-share pylon_ros2_camera_wrapper)/launch/pylon_ros2_camera.launch.py">
<arg name="node_name" value="ceiling_cam_publisher"/>
<arg name="camera_id" value="ceiling_cam"/>
<arg name="config_file" value="$(find-pkg-share bitbots_ceiling_cam)/config/camera_settings_ceiling_cam.yaml" />
</include>
<node pkg="bitbots_basler_camera" exec="basler_camera" name="ceiling_cam_publisher" output="screen" launch-prefix="$(var taskset)">
<param from="$(find-pkg-share bitbots_ceiling_cam)/config/camera_settings_ceiling_cam.yaml">
<remap from="/camera/image_proc" to="/ceiling_cam/ceiling_cam_publisher/image_proc"/>
<remap from="/camera/camera_info" to="/ceiling_cam/ceiling_cam_publisher/camera_info"/>
</node>

<!-- image processing and apriltag detection -->
<node_container pkg="rclcpp_components" exec="component_container" name="ceiling_cam_image_proc_container" namespace="">
<composable_node pkg="image_proc" plugin="image_proc::DebayerNode" name="debayer">
<remap from="image_raw" to="/ceiling_cam/ceiling_cam_publisher/image_raw"/>
<remap from="camera_info" to="/ceiling_cam/ceiling_cam_publisher/camera_info"/>
<remap from="image_color" to="/ceiling_cam/ceiling_cam_publisher/image_color_debayered"/>
</composable_node>
<composable_node pkg="image_proc" plugin="image_proc::RectifyNode" name="rectify">
<remap from="image" to="/ceiling_cam/ceiling_cam_publisher/image_color_debayered"/>
<remap from="image" to="/ceiling_cam/ceiling_cam_publisher/image_proc"/>
<remap from="camera_info" to="/ceiling_cam/ceiling_cam_publisher/camera_info"/>
<remap from="image_rect" to="/ceiling_cam/ceiling_cam_publisher/image_color_rect"/>
<remap from="image_rect" to="/ceiling_cam/ceiling_cam_publisher/image_proc_rect"/>
</composable_node>
<composable_node pkg="apriltag_ros" plugin="AprilTagNode" name="apriltag">
<remap from="/apriltag/image" to="/ceiling_cam/ceiling_cam_publisher/image_color_rect"/>
<remap from="/apriltag/image" to="/ceiling_cam/ceiling_cam_publisher/image_proc_rect"/>
<remap from="/apriltag/camera_info" to="/ceiling_cam/ceiling_cam_publisher/camera_info"/>
<param from="$(find-pkg-share bitbots_ceiling_cam)/config/april_tags.yaml"/>
</composable_node>
</node_container>


</launch>
5 changes: 3 additions & 2 deletions bitbots_misc/bitbots_ceiling_cam/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,14 @@

<maintainer email="[email protected]">Marc Bestmann</maintainer>
<maintainer email="[email protected]">Hamburg Bit-Bots</maintainer>

<license>MIT</license>

<author email="[email protected]">Hamburg Bit-Bots</author>

<depend>apriltag_ros</depend>
<depend>bitbots_basler_camera</depend>
<depend>bitbots_docs</depend>
<depend>pylon_ros2_camera_wrapper</depend>
<depend>image_proc</depend>
<depend>tf2_ros</depend>

Expand Down

0 comments on commit c9f8dbb

Please sign in to comment.