Skip to content

Commit a79c509

Browse files
authored
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
1 parent da37069 commit a79c509

File tree

12 files changed

+374
-42
lines changed

12 files changed

+374
-42
lines changed
Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2+
Changelog for package pointgrey_camera_description
3+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4+
5+
0.1.0 (2021-11-10)
6+
-------------------
7+
* Initial Release
8+
* Contributors: Luis Camero
9+
Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(flir_camera_description)
3+
4+
find_package(catkin REQUIRED)
5+
6+
catkin_package()
7+
8+
install(DIRECTORY launch meshes rviz urdf
9+
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
10+
)
343 KB
Binary file not shown.
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
<?xml version="1.0"?>
2+
<package format="2">
3+
<name>flir_camera_description</name>
4+
<version>0.1.0</version>
5+
<description>URDF descriptions for Flir cameras</description>
6+
7+
<maintainer email="[email protected]">Luis Camero</maintainer>
8+
9+
<license>BSD</license>
10+
11+
<buildtool_depend>catkin</buildtool_depend>
12+
<exec_depend>robot_state_publisher</exec_depend>
13+
<exec_depend>urdf</exec_depend>
14+
<exec_depend>xacro</exec_depend>
15+
</package>
Lines changed: 108 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="flir_blackflys">
3+
<!--
4+
camera_{x,y,z,mass} are physical properties of camera collision model
5+
lens_{r, h, mass} are physical properties of the camera lens
6+
hfov, fps, width, height, format, near, and far are simulation
7+
-->
8+
<xacro:macro name="flir_blackflys"
9+
params="frame:=camera name:=camera camera_x:=0.047758 camera_y:=0.029 camera_z:=0.029 camera_mass:=0.03
10+
lens_r:=0.016 lens_h:=0.04 lens_mass:= 0.05
11+
hfov:=1.0471975512 fps:=30 width:=720 height:=540 format:=R8G8B8 near:=0.5 far:=300">
12+
13+
<link name="${frame}">
14+
<inertial>
15+
<mass value="${camera_mass}" />
16+
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
17+
</inertial>
18+
<visual>
19+
<origin xyz="0 0 0.01425" rpy="0 0 0" />
20+
<geometry>
21+
<mesh filename="package://flir_camera_description/meshes/flir_blackflys.stl"/>
22+
</geometry>
23+
<material name="dark_grey" />
24+
</visual>
25+
<collision>
26+
<origin xyz="0.003 0 ${camera_z/2}" rpy="0 0 0" />
27+
<geometry>
28+
<box size="${camera_x} ${camera_y} ${camera_z}" />
29+
</geometry>
30+
</collision>
31+
</link>
32+
33+
<link name="${frame}_lens">
34+
<intertial>
35+
<mass values="${lens_mass}" />
36+
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
37+
</intertial>
38+
<visual>
39+
<origin xyz="${lens_h/2} 0 0" rpy="0 1.5707 0" />
40+
<geometry>
41+
<cylinder radius="${lens_r}" length="${lens_h}"/>
42+
</geometry>
43+
<material name="dark_grey" />
44+
</visual>
45+
<collision>
46+
<origin xyz="${lens_h/2} 0 0" rpy="0 1.5707 0" />
47+
<geometry>
48+
<cylinder radius="${lens_r}" length="${lens_h}"/>
49+
</geometry>
50+
</collision>
51+
</link>
52+
53+
<link name="${frame}_optical" />
54+
55+
<joint name="${frame}_lens_joint" type="fixed">
56+
<origin xyz="0.02685 0 0.01425" rpy="0 0 0" />
57+
<parent link="${frame}" />
58+
<child link="${frame}_lens" />
59+
</joint>
60+
61+
<joint name="${frame}_optical_joint" type="fixed">
62+
<origin xyz="${lens_h} 0 0" rpy="-1.570796 0 -1.570796" />
63+
<parent link="${frame}_lens" />
64+
<child link="${frame}_optical" />
65+
</joint>
66+
67+
<!-- Gazebo -->
68+
<gazebo reference="${frame}_optical">
69+
<material>Gazebo/Grey</material>
70+
<sensor type="camera" name="${name}">
71+
<update_rate>${fps}</update_rate>
72+
<camera name="${name}">
73+
<pose>0 0 0 0 -1.5707 1.5707</pose>
74+
<horizontal_fov>${hfov}</horizontal_fov>
75+
<image>
76+
<width>${width}</width>
77+
<height>${height}</height>
78+
<format>${format}</format>
79+
</image>
80+
<clip>
81+
<near>${near}</near>
82+
<far>${far}</far>
83+
</clip>
84+
<noise>
85+
<type>gaussian</type>
86+
<mean>0.0</mean>
87+
<stddev>0.007</stddev>
88+
</noise>
89+
</camera>
90+
91+
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
92+
<alwaysOn>true</alwaysOn>
93+
<updateRate>${fps}</updateRate>
94+
<cameraName>${name}</cameraName>
95+
<imageTopicName>image_raw</imageTopicName>
96+
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
97+
<frameName>${frame}_optical</frameName>
98+
<hackBaseline>0.07</hackBaseline>
99+
<distortionK1>0.0</distortionK1>
100+
<distortionK2>0.0</distortionK2>
101+
<distortionK3>0.0</distortionK3>
102+
<distortionT1>0.0</distortionT1>
103+
<distortionT2>0.0</distortionT2>
104+
</plugin>
105+
</sensor>
106+
</gazebo>
107+
</xacro:macro>
108+
</robot>

spinnaker_camera_driver/cfg/Spinnaker.cfg

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -78,18 +78,21 @@ gen = ParameterGenerator()
7878
gen.add("acquisition_frame_rate", double_t, SensorLevels.RECONFIGURE_RUNNING, "User controlled acquisition frame rate in Hertz (frames per second).", 10, 0, 120)
7979
gen.add("acquisition_frame_rate_enable", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enables manual (True) and automatic (False) control of the aquisition frame rate", False)
8080

81-
8281
# Set Exposure
8382
# Note: For the Auto Exposure feature, gain and/or exposure time must be set to Once or Continuous.
83+
capture_modes = gen.enum([gen.const("AutoOff", str_t, "Off", ""),
84+
gen.const("AutoOnce", str_t, "Once", ""),
85+
gen.const("AutoContinuous", str_t, "Continuous", "")],
86+
"Automatic mode: Off, Once, or Continuous.")
8487
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)
8689
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)
8790
gen.add("auto_exposure_time_upper_limit", double_t, SensorLevels.RECONFIGURE_RUNNING, "Upper Limit on Shutter Speed.", 5000, 0.0, 3000000.0)
8891

8992

9093
# Gain Settings
9194
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")
95+
gen.add("auto_gain", str_t, SensorLevels.RECONFIGURE_RUNNING, "Gain state control. (Off, Once, Continuous)", "Continuous", edit_method=capture_modes)
9396
gen.add("gain", double_t, SensorLevels.RECONFIGURE_RUNNING, "Controls the amplification of the video signal in dB.", 0, -10, 30)
9497

9598
# Pan and Tilt not in Spinnaker Driver
@@ -113,7 +116,7 @@ gen.add("gamma", double_t, SensorLevels.RECON
113116

114117

115118
# White Balance
116-
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)
117120
gen.add("white_balance_blue_ratio", double_t, SensorLevels.RECONFIGURE_RUNNING, "White balance blue component.", 800, 0, 1023)
118121
gen.add("white_balance_red_ratio", double_t, SensorLevels.RECONFIGURE_RUNNING, "White balance red component.", 550, 0, 1023)
119122

@@ -174,7 +177,8 @@ codings = gen.enum([gen.const("Mono8", str_t, "Mono8", ""),
174177

175178
"Image Color Coding: Format of the pixel provided by the camera.")
176179

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)
178182

179183

180184
# Trigger parameters

spinnaker_camera_driver/include/spinnaker_camera_driver/diagnostics.h

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,9 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
4545
#include "spinnaker_camera_driver/diagnostics.h"
4646
#include <diagnostic_msgs/DiagnosticArray.h>
4747
#include <diagnostic_msgs/DiagnosticStatus.h>
48+
#include <diagnostic_msgs/AddDiagnostics.h>
4849
#include <ros/ros.h>
50+
#include <bondcpp/bond.h>
4951

5052
#include <utility>
5153
#include <string>
@@ -56,7 +58,7 @@ namespace spinnaker_camera_driver
5658
class DiagnosticsManager
5759
{
5860
public:
59-
DiagnosticsManager(const std::string name, const std::string serial, std::shared_ptr<ros::Publisher> const& pub);
61+
DiagnosticsManager(const std::string name, const std::string serial, std::shared_ptr<ros::Publisher> const& pub, ros::NodeHandle& nh);
6062
~DiagnosticsManager();
6163

6264
/*!
@@ -95,6 +97,8 @@ class DiagnosticsManager
9597
std::pair<float, float> operational = std::make_pair(0.0, 0.0), float lower_bound = 0,
9698
float upper_bound = 0);
9799

100+
void addAnalyzers();
101+
98102
private:
99103
/*
100104
* diagnostic_params is aData Structure to represent a parameter and its
@@ -126,6 +130,8 @@ class DiagnosticsManager
126130
// constuctor parameters
127131
std::string camera_name_;
128132
std::string serial_number_;
133+
ros::NodeHandle nh_;
134+
std::shared_ptr<bond::Bond> bond_ = nullptr;
129135
std::shared_ptr<ros::Publisher> diagnostics_pub_;
130136

131137
// vectors to keep track of the items to publish

spinnaker_camera_driver/launch/camera.launch

Lines changed: 51 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -29,30 +29,77 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
2929
<arg name="camera_name" default="camera" />
3030
<arg name="camera_serial" default="0" />
3131
<arg name="calibrated" default="0" />
32-
<arg name="device_type" default="GigE" /> <!-- USB3 or GigE -->
32+
<arg name="device_type" default="USB3" /> <!-- USB3 or GigE -->
3333

3434
<!-- When unspecified, the driver will use the default framerate as given by the
3535
camera itself. Use the parameter 'control_frame_rate' to enable manual frame
3636
rate control, and 'frame_rate' to set the frame rate value. -->
37-
<arg name="control_frame_rate" default="false" />
37+
<arg name="control_frame_rate" default="True" />
3838
<arg name="frame_rate" default="30" />
3939

40+
<!-- Disabling ISP will dramatically increase frame-rate. However, it can only be
41+
disabled when using Bayer encoding (e.g. BayerRG8)-->
42+
<arg name="isp_enable" default="False" />
43+
<arg name="encoding" default="BayerRG8" />
44+
<arg name="color_balance" default="Continuous" /> <!-- Off, Once, or Continuous -->
45+
<!-- Available Encodings:
46+
Mono: YUV: YCbCr: Other:
47+
- Mono8 - YUV411Packed - YCbCr8 - BGR8
48+
- Mono16 - YUV422Packed - YCbCr422_8 - BGRa8
49+
- Mono12p - YUV444Packed - YCbCr411_8 - RGB8Packed
50+
- Mono12Packed
51+
52+
Bayer:
53+
- BayerGR8 - BayerGR12p
54+
- BayerRG8 - BayerRG12p
55+
- BayerGB8 - BayerGB12p
56+
- BayerBG8 - BayerBG12p
57+
- BayerGR16 - BayerGR12Packed
58+
- BayerRG16 - BayerRG12Packed
59+
- BayerGB16 - BayerGB12Packed
60+
- BayerBG16 - BayerBG12Packed
61+
-->
62+
4063
<group ns="$(arg camera_name)">
4164
<!-- Nodelet manager -->
4265
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" cwd="node" output="screen"/>
43-
66+
->
4467
<!-- Camera nodelet -->
4568
<node pkg="nodelet" type="nodelet" name="spinnaker_camera_nodelet"
4669
args="load spinnaker_camera_driver/SpinnakerCameraNodelet camera_nodelet_manager" >
4770

48-
<param name="frame_id" value="camera" />
71+
<param name="frame_id" value="$(arg camera_name)" />
4972
<param name="serial" value="$(arg camera_serial)" />
5073
<param name="device_type" value="$(arg device_type)" />
5174

5275
<!-- Frame rate -->
5376
<param name="acquisition_frame_rate_enable" value="$(arg control_frame_rate)" />
5477
<param name="acquisition_frame_rate" value="$(arg frame_rate)" />
5578

79+
<!-- Image Processing -->
80+
<param name="isp_enable" value="$(arg isp_enable)" />
81+
<param name="auto_white_balance" value="$(arg color_balance)" />
82+
<param name="image_format_color_coding" value="$(arg encoding)" />
83+
84+
<!-- Image Resolution -->
85+
<!-- Height and width pixel size cannot be set directly. Instead use the
86+
binning, offset, and region of interest options.
87+
- RoI: range of pixels to select from original image
88+
(Note: RoI is defined from image pixel origin (i.e. top left))
89+
- Binning: reduces resolution by a factor of 1, 2, 4, or 8
90+
- Offset: moves the pixel origin
91+
x-offset = max_width/x_binning - roi_width/2
92+
y-offset = max_height/y_binning - roi_height/2
93+
-->
94+
<!--
95+
<param name="image_format_x_binning" value="2" />
96+
<param name="image_format_y_binning" value="2" />
97+
<param name="image_format_x_offset" value="128" />
98+
<param name="image_format_y_offset" value="122" />
99+
<param name="image_format_roi_width" value="1280" />
100+
<param name="image_format_roi_height" value="720" />
101+
-->
102+
56103
<!-- Use the camera_calibration package to create this file -->
57104
<param name="camera_info_url" if="$(arg calibrated)"
58105
value="file://$(env HOME)/.ros/camera_info/$(arg camera_serial).yaml" />

0 commit comments

Comments
 (0)