berndpfrommer / flir_spinnaker_ros2

ros2 driver for flir spinnaker SDK
26 stars 27 forks source link

problem with automatic exposure #41

Closed dariodenardi closed 1 year ago

dariodenardi commented 1 year ago

Hi,

I have a problem with automatic exposure. When I use the cameras and there is good weather the photo becomes ugly to see.

good weather I mean normal light in the environment (no sun against the camera)

at this point I don't know if the automatic check works correctly:

I use Blackfly S. Here is an example of an image:

1680167421 938577064

same effect with one and two cameras

Launch file of only one camera (no synced):

# Copyright 2022 Bernd Pfrommer <bernd.pfrommer@gmail.com>
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#     http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
#

from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration as LaunchConfig
from launch.actions import DeclareLaunchArgument as LaunchArg
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory

camera_params = {
    'debug': False,
    'compute_brightness': True,
    'adjust_timestamp': True,
    'dump_node_map': False,
    # set parameters defined in blackfly_s.cfg
    'gain_auto': 'Off',
    'gain': 20.0,
    'exposure_auto': 'Off',
    'exposure_time': 10000,
    # 'device_link_throughput_limit': 380000000,
    # ---- to reduce the sensor width and shift the crop
    # 'image_width': 1408,
    # 'image_height': 1080,
    # 'offset_x': 16,
    # 'offset_y': 0,
    'frame_rate_auto': 'Off',
    'frame_rate': 20.0,
    'frame_rate_enable': True,
    'buffer_queue_size': 1,
    'trigger_mode': 'Off',
    'chunk_mode_active': True,
    'chunk_selector_frame_id': 'FrameID',
    'chunk_enable_frame_id': True,
    'chunk_selector_exposure_time': 'ExposureTime',
    'chunk_enable_exposure_time': True,
    'chunk_selector_gain': 'Gain',
    'chunk_enable_gain': True,
    'chunk_selector_timestamp': 'Timestamp',
    'chunk_enable_timestamp': True,
    }

def generate_launch_description():
    flir_dir = get_package_share_directory('flir_spinnaker_ros2')
    config_dir = flir_dir + '/config/'
    name_arg = LaunchArg('camera_name', default_value='blackfly_s',
                         description='camera name')
    serial_arg = LaunchArg('serial', default_value="'20435008'",
                           description='serial number')

    node = Node(package='flir_spinnaker_ros2',
                executable='camera_driver_node',
                output='screen',
                name=[LaunchConfig('camera_name')],
                parameters=[camera_params,
                            {'parameter_file': config_dir + 'blackfly_s.cfg',
                             'serial_number': [LaunchConfig('serial')]}],
                remappings=[('~/control', '/exposure_control/control'), ])

    return LaunchDescription([name_arg, serial_arg, node])

My questions:

berndpfrommer commented 1 year ago

There are two ways to achieve auto-exposure: 1) enable the camera's built-in auto exposure. From your launch file you have currently switched that to "off". Switching that to "On" should give you success. You may want to first explore the camera's behavior with SpinView to see if you like how that auto exposure works. 2) use an external exposure controller, i.e. a separate software package that runs independently. I implemented this because I am using a pair of cameras for visual odometry where it is important that the left and right cameras have identical exposure setting. To use this you will have to install two additional packages for camera synchronization and exposure control referenced in this launch file. Unless you are planning on doing visual odometry with stereo cameras, I recommend using method 1) above.

dariodenardi commented 1 year ago

thank you for the answer

is it possibile that my camera haven't brightness? I 'compute_brightness': True but if I print /cam_0/meta, brightness is always 0


  stamp:
    sec: 1680350583
    nanosec: 766597729
  frame_id: cam_0
camera_time: 6744059481944
brightness: 0
exposure_time: 9501
max_exposure_time: 29999999
gain: 0.0```
berndpfrommer commented 1 year ago

Not sure why the brightness computation does not work. Do you want to use the external method at all? Why not just switch on auto exposure at the camera level?

dariodenardi commented 1 year ago

because I have to use two cameras

Is there any way to see why it's not working right?

berndpfrommer commented 1 year ago

What do you need two cameras for?

dariodenardi commented 1 year ago

I need it to create a stereo system...so i use two cameras that i set them to master-slave mode

I need to acquire two images at the same time but I have this problem with the exposure

berndpfrommer commented 1 year ago

I implemented external auto exposure for my specific needs but it has not seen too much usage. Your mileage may vary. One of the reasons the brightness calculation fails is that I only implemented for one particular pixel format. Put some print statements into this routine to see if a) it is called at all, and b) if the pixel format is bayer as required and c) what it actually calculates. https://github.com/berndpfrommer/flir_spinnaker_common/blob/e33fa73d0bc90cf880216f827c83d046f916141c/src/driver_impl.cpp#L263

dariodenardi commented 1 year ago

thank you, I solved

I setted the pixel format to bgr8. for me it is not a problem to use bayer

maybe i recommend adding a line in the readme