You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
URDF Description, Diagnostics, ISP Enable, and Launch Files (#81)
* Changes required to use GigE Blackfly S version
* Added blackfly mesh
* Added URDF of blackflys and CHANGELOG
* Added new_line at end of flir_blackflys.urdf.xacro
* Added DiagnosticAnalyzers and more detailed diagnostic messages
* Added ISP enable and disable config and updated camera launch file to be more descriptive
* Switched order of configuration to put ISP enable next to color encoding
* Updated config to include enumeration for Off, Once, Continuous parameters, and udpated diagnostics.launch
* Handled issue where no namespace prevents diagnostics_agg from loading from analyzer paramaters
Copy file name to clipboardExpand all lines: spinnaker_camera_driver/cfg/Spinnaker.cfg
+9-5Lines changed: 9 additions & 5 deletions
Original file line number
Diff line number
Diff line change
@@ -78,18 +78,21 @@ gen = ParameterGenerator()
78
78
gen.add("acquisition_frame_rate", double_t, SensorLevels.RECONFIGURE_RUNNING, "User controlled acquisition frame rate in Hertz (frames per second).", 10, 0, 120)
79
79
gen.add("acquisition_frame_rate_enable", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enables manual (True) and automatic (False) control of the aquisition frame rate", False)
80
80
81
-
82
81
# Set Exposure
83
82
# Note: For the Auto Exposure feature, gain and/or exposure time must be set to Once or Continuous.
gen.add("exposure_mode", str_t, SensorLevels.RECONFIGURE_STOP, "Sets the operation mode of the Exposure (Timed or TriggerWidth).", "Timed")
85
-
gen.add("exposure_auto", str_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the automatic exposure mode to: 'Off', 'Once' or 'Continuous'", "Continuous")
88
+
gen.add("exposure_auto", str_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the automatic exposure mode to: 'Off', 'Once' or 'Continuous'", "Continuous", edit_method=capture_modes)
86
89
gen.add("exposure_time", double_t, SensorLevels.RECONFIGURE_RUNNING, "Exposure time in microseconds when Exposure Mode is Timed and Exposure Auto is not Continuous.", 100.0, 0.0, 3000000.0)
gen.add("gain_selector", str_t, SensorLevels.RECONFIGURE_RUNNING, "Selects which gain to control. The All selection is a total amplification across all channels.", "All")
92
-
gen.add("auto_gain", str_t, SensorLevels.RECONFIGURE_RUNNING, "Gain state control. (Off, Once, Continuous)", "Continuous")
gen.add("auto_white_balance", str_t, SensorLevels.RECONFIGURE_RUNNING, "White Balance compensates for color shifts caused by different lighting conditions.", "Off")
119
+
gen.add("auto_white_balance", str_t, SensorLevels.RECONFIGURE_RUNNING, "White Balance compensates for color shifts caused by different lighting conditions.", "Off", edit_method=capture_modes)
117
120
gen.add("white_balance_blue_ratio", double_t, SensorLevels.RECONFIGURE_RUNNING, "White balance blue component.", 800, 0, 1023)
118
121
gen.add("white_balance_red_ratio", double_t, SensorLevels.RECONFIGURE_RUNNING, "White balance red component.", 550, 0, 1023)
"Image Color Coding: Format of the pixel provided by the camera.")
176
179
177
-
gen.add("image_format_color_coding", str_t, SensorLevels.RECONFIGURE_STOP, "Image Color coding", "Mono8", edit_method=codings)
180
+
gen.add("image_format_color_coding", str_t, SensorLevels.RECONFIGURE_STOP, "Image Color coding", "Mono8", edit_method=codings)
181
+
gen.add("isp_enable", bool_t, SensorLevels.RECONFIGURE_STOP, "Controls whether the image processing core is used for optional pixel format mode", True)
0 commit comments