From bf25bb9bd09b176fc9105b985274a27a450cb65e Mon Sep 17 00:00:00 2001 From: anonymousarmadillo100 Date: Fri, 17 May 2024 12:35:18 -0500 Subject: [PATCH 1/4] flir_ax5 config file --- spinnaker_camera_driver/config/flir_ax5.yaml | 67 ++++++++++++++++++++ 1 file changed, 67 insertions(+) create mode 100644 spinnaker_camera_driver/config/flir_ax5.yaml diff --git a/spinnaker_camera_driver/config/flir_ax5.yaml b/spinnaker_camera_driver/config/flir_ax5.yaml new file mode 100644 index 0000000..0364db1 --- /dev/null +++ b/spinnaker_camera_driver/config/flir_ax5.yaml @@ -0,0 +1,67 @@ +# +# config file for FLIR AX5 cameras (GigE) +# +# This file maps the ros parameters to the corresponding Spinnaker "nodes" in the camera. +# For more details on how to modify this file, see the README on camera configuration files. +# Spinview method: double-click on nodes (under the features tab) to see their actual name and allowed values. + +parameters: + # + # -------- image format control + # + - name: pixel_format + type: enum + # default is "Mono8" + node: ImageFormatControl/PixelFormat + - name: image_width + type: int + node: ImageFormatControl/Width + - name: image_height + type: int + node: ImageFormatControl/Height + - name: offset_x # offset must come after image width reduction! + type: int + node: ImageFormatControl/OffsetX + - name: offset_y + type: int + node: ImageFormatControl/OffsetY + + # + # -------- transport layer control (GigE) + # + - name: gev_scps_packet_size + type: int + # default is 576. Other cameras had the option to set to 9000 to enable jumbo frames, ensure NIC MTU set >= 9000 + node: TransportLayerControl/GevSCPSPacketSize + + # + # ---------- FLIR Camera Control + # + - name: sensor_gain_mode + type: enum + # valid values: "HighGainMode" "LowGainMode" + node: CameraControl/SensorGainMode + - name: nuc_mode # Non-uniformity Control closes the shutter and recalibrates + type: enum + # valid values: "Automatic" "External" "Manual" + node: CameraControl/NUCMode + - name: sensor_dde_mode + type: enum + # valid values: "Automatic" "Manual" (DDE = Digital Detail Enhancement) + node: CameraControl/SensorDDEMode + + # + # ---------- FLIR Video Control + # + - name: sensor_video_standard + type: enum + # valid values: "NTSC30HZ" "PAL25Hz" "NTSC60HZ" "PAL50HZ" (affects framerate) + node: Mono8VideoControl/SensorVideoStandard + - name: image_adjust_method + type: enum + # valid values: "PlateauHistogram" "OnceBright" "AutoBright" "Manual" "Linear" + node: Mono8VideoControl/ImageAdjustMethod + - name: video_orientation + type: enum + # valid values: "Normal" "Invert" "Revert" "InvertRevert" + node: Mono8VideoControl/VideoOrientation \ No newline at end of file From 84550b3e4673781e9b4f499c3df68537dd64f358 Mon Sep 17 00:00:00 2001 From: anonymousarmadillo100 Date: Fri, 17 May 2024 12:38:06 -0500 Subject: [PATCH 2/4] Update driver_node.launch.py --- .../launch/driver_node.launch.py | 21 ++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/spinnaker_camera_driver/launch/driver_node.launch.py b/spinnaker_camera_driver/launch/driver_node.launch.py index b1445a6..3b7014c 100644 --- a/spinnaker_camera_driver/launch/driver_node.launch.py +++ b/spinnaker_camera_driver/launch/driver_node.launch.py @@ -102,7 +102,26 @@ 'chunk_selector_gain': 'Gain', 'chunk_enable_gain': True, 'chunk_selector_timestamp': 'Timestamp', - 'chunk_enable_timestamp': True} + 'chunk_enable_timestamp': True}, + 'flir_ax5': { + 'debug': False, + 'compute_brightness': False, + 'adjust_timestamp': False, + 'dump_node_map': False, + # --- Set parameters defined in flir_ax5.yaml + 'pixel_format': 'Mono8', + 'gev_scps_packet_size': 576, + 'image_width': 640, + 'image_height': 512, + 'offset_x': 0, + 'offset_y': 0, + 'sensor_gain_mode': 'HighGainMode', # "HighGainMode" "LowGainMode" + 'nuc_mode': 'Automatic', #"Automatic" "External" "Manual" + 'sensor_dde_mode':'Automatic', #"Automatic" "Manual" + 'sensor_video_standard':'NTSC30HZ', #"NTSC30HZ" "PAL25Hz" "NTSC60HZ" "PAL50HZ" + 'image_adjust_method':'PlateauHistogram', #"PlateauHistogram" "OnceBright" "AutoBright" "Manual" "Linear" + 'video_orientation':'Normal' #"Normal" "Invert" "Revert" "InvertRevert" + } } From 09a0107fb66a584330208a79732e8e16db9a3fe0 Mon Sep 17 00:00:00 2001 From: anonymousarmadillo100 Date: Fri, 17 May 2024 12:42:53 -0500 Subject: [PATCH 3/4] Update index.rst --- spinnaker_camera_driver/doc/index.rst | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/spinnaker_camera_driver/doc/index.rst b/spinnaker_camera_driver/doc/index.rst index 6ec9546..a1816df 100644 --- a/spinnaker_camera_driver/doc/index.rst +++ b/spinnaker_camera_driver/doc/index.rst @@ -28,6 +28,7 @@ The following cameras have been successfully used with this driver: - Grashopper (USB3) - Oryx (reported working) - Chameleon (USB3, tested on firmware v1.13.3.00) +- FLIR AX5 (GigE) Note: if you get other cameras to work, *please report back*, ideally submit a pull request with the camera config file you have created. @@ -206,7 +207,7 @@ Blackfly S the parameters look like this: -Setting up GigE cameras +Network Configuration for GigE cameras ======================= The Spinnaker SDK abstracts away the transport layer so a GigE camera @@ -247,6 +248,14 @@ needing to spin up a custom launch file to get started, though it helps, and you’ll probably want one anyway to specify your camera’s serial number. +If you do not set up DHCP or set a static IP, your camera will probably +assign itself an IP address according to the Link-Local address scheme. +The address will be 169.254.xxx.xxx, where the x's are randomly generated. +In your computer's network settings, change the IPv4 Method for the port +that connects to your camera to "Link-Local Only." (You could also set +the IPv4 Method to "Manual" with an address of 169.254.100.1 and a +subnet mask of 255.255.0.0). + For more tips on GigE setup look at FLIR’s support pages `here `__ and @@ -291,10 +300,12 @@ valid enum strings in the configuration file, e.g.: node: DigitalIOControl/LineMode The hard part is often finding the node name, in the last example -``"DigitalIOControl/LineMode"``. It usually follows by removing spaces -from the ``spinview`` names. If that doesn’t work, launch the driver -with the ``dump_node_map`` parameter set to “True” and look at the -output for inspiration. +``"DigitalIOControl/LineMode"``. It usually follows by removing spaces +from the ``spinview`` display names. However, in the SpinView GUI you +can also see the true name by double-clicking on a node under the +features tab and looking for "Name" (as opposed to "Display Name"). +If that doesn't work, launch the driver with the ``dump_node_map`` +parameter set to "True" and look at the output for inspiration. **NOTE: !!!! THE ORDER OF PARAMETER DEFINITION MATTERS !!!!** From 91d933d32dde2750ada37fdde047477e8c19af93 Mon Sep 17 00:00:00 2001 From: Bernd Pfrommer Date: Sat, 18 May 2024 08:02:40 -0400 Subject: [PATCH 4/4] fix python formatting test failures --- .../launch/driver_node.launch.py | 94 ++++++++++++------- 1 file changed, 59 insertions(+), 35 deletions(-) diff --git a/spinnaker_camera_driver/launch/driver_node.launch.py b/spinnaker_camera_driver/launch/driver_node.launch.py index 3b7014c..9dba13c 100644 --- a/spinnaker_camera_driver/launch/driver_node.launch.py +++ b/spinnaker_camera_driver/launch/driver_node.launch.py @@ -20,11 +20,9 @@ from launch.actions import OpaqueFunction from launch.substitutions import LaunchConfiguration as LaunchConfig from launch.substitutions import PathJoinSubstitution - from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare - example_parameters = { 'blackfly_s': { 'debug': False, @@ -59,7 +57,8 @@ 'chunk_selector_gain': 'Gain', 'chunk_enable_gain': True, 'chunk_selector_timestamp': 'Timestamp', - 'chunk_enable_timestamp': True}, + 'chunk_enable_timestamp': True, + }, 'chameleon': { 'debug': False, 'compute_brightness': False, @@ -83,7 +82,8 @@ 'chunk_selector_gain': 'Gain', 'chunk_enable_gain': True, 'chunk_selector_timestamp': 'Timestamp', - 'chunk_enable_timestamp': True}, + 'chunk_enable_timestamp': True, + }, 'grasshopper': { 'debug': False, 'compute_brightness': False, @@ -102,7 +102,8 @@ 'chunk_selector_gain': 'Gain', 'chunk_enable_gain': True, 'chunk_selector_timestamp': 'Timestamp', - 'chunk_enable_timestamp': True}, + 'chunk_enable_timestamp': True, + }, 'flir_ax5': { 'debug': False, 'compute_brightness': False, @@ -115,14 +116,15 @@ 'image_height': 512, 'offset_x': 0, 'offset_y': 0, - 'sensor_gain_mode': 'HighGainMode', # "HighGainMode" "LowGainMode" - 'nuc_mode': 'Automatic', #"Automatic" "External" "Manual" - 'sensor_dde_mode':'Automatic', #"Automatic" "Manual" - 'sensor_video_standard':'NTSC30HZ', #"NTSC30HZ" "PAL25Hz" "NTSC60HZ" "PAL50HZ" - 'image_adjust_method':'PlateauHistogram', #"PlateauHistogram" "OnceBright" "AutoBright" "Manual" "Linear" - 'video_orientation':'Normal' #"Normal" "Invert" "Revert" "InvertRevert" - } - } + 'sensor_gain_mode': 'HighGainMode', # "HighGainMode" "LowGainMode" + 'nuc_mode': 'Automatic', # "Automatic" "External" "Manual" + 'sensor_dde_mode': 'Automatic', # "Automatic" "Manual" + 'sensor_video_standard': 'NTSC30HZ', # "NTSC30HZ" "PAL25Hz" "NTSC60HZ" "PAL50HZ" + # valid values: "PlateauHistogram" "OnceBright" "AutoBright" "Manual" "Linear" + 'image_adjust_method': 'PlateauHistogram', + 'video_orientation': 'Normal', # "Normal" "Invert" "Revert" "InvertRevert" + }, +} def launch_setup(context, *args, **kwargs): @@ -131,34 +133,56 @@ def launch_setup(context, *args, **kwargs): camera_type = LaunchConfig('camera_type').perform(context) if not parameter_file: parameter_file = PathJoinSubstitution( - [FindPackageShare('spinnaker_camera_driver'), 'config', - camera_type + '.yaml']) + [FindPackageShare('spinnaker_camera_driver'), 'config', camera_type + '.yaml'] + ) if camera_type not in example_parameters: raise Exception('no example parameters available for type ' + camera_type) - node = Node(package='spinnaker_camera_driver', - executable='camera_driver_node', - output='screen', - name=[LaunchConfig('camera_name')], - parameters=[example_parameters[camera_type], - {'ffmpeg_image_transport.encoding': 'hevc_nvenc', - 'parameter_file': parameter_file, - 'serial_number': [LaunchConfig('serial')]}], - remappings=[('~/control', '/exposure_control/control'), ]) + node = Node( + package='spinnaker_camera_driver', + executable='camera_driver_node', + output='screen', + name=[LaunchConfig('camera_name')], + parameters=[ + example_parameters[camera_type], + { + 'ffmpeg_image_transport.encoding': 'hevc_nvenc', + 'parameter_file': parameter_file, + 'serial_number': [LaunchConfig('serial')], + }, + ], + remappings=[ + ('~/control', '/exposure_control/control'), + ], + ) return [node] def generate_launch_description(): """Create composable node by calling opaque function.""" - return LaunchDescription([ - LaunchArg('camera_name', default_value=['flir_camera'], - description='camera name (ros node name)'), - LaunchArg('camera_type', default_value='blackfly_s', - description='type of camera (blackfly_s, chameleon...)'), - LaunchArg('serial', default_value="'20435008'", - description='FLIR serial number of camera (in quotes!!)'), - LaunchArg('parameter_file', default_value='', - description='path to ros parameter definition file (override camera type)'), - OpaqueFunction(function=launch_setup) - ]) + return LaunchDescription( + [ + LaunchArg( + 'camera_name', + default_value=['flir_camera'], + description='camera name (ros node name)', + ), + LaunchArg( + 'camera_type', + default_value='blackfly_s', + description='type of camera (blackfly_s, chameleon...)', + ), + LaunchArg( + 'serial', + default_value="'20435008'", + description='FLIR serial number of camera (in quotes!!)', + ), + LaunchArg( + 'parameter_file', + default_value='', + description='path to ros parameter definition file (override camera type)', + ), + OpaqueFunction(function=launch_setup), + ] + )