Skip to content

Commit

Permalink
checkout launch files and xml files + minor manual transfers from devel
Browse files Browse the repository at this point in the history
  • Loading branch information
Guillaume Caron committed Sep 26, 2024
1 parent 9f26bf5 commit fd341a1
Show file tree
Hide file tree
Showing 22 changed files with 856 additions and 2 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ find_package(catkin REQUIRED COMPONENTS
sensor_msgs
image_transport
visp_bridge
rosbag
)

## System dependencies are found with CMake's conventions
Expand Down
9 changes: 9 additions & 0 deletions config/FL3-U3toUR10flange.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
rows: 6
cols: 1
data:
- [-0.078]
- [0.0]
- [0.02]
- [0.0]
- [0.0]
- [-1.5700]
16 changes: 16 additions & 0 deletions config/calib_equi_224_112.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<root>
<!--PR team of the MIS lab - UPJV - France-->
<camera>
<!--Name of the camera-->
<name>Equirectangular</name>
<!--Type of the camera-->
<type>4</type>
<!--Pixel ratio-->
<au>35.650707252</au>
<av>35.650707252</av>
<!--Principal point-->
<u0>112.0000000000</u0>
<v0>56.0000000000</v0>
</camera>
</root>
16 changes: 16 additions & 0 deletions config/calib_equi_92_46.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<root>
<!--PR team of the MIS lab - UPJV - France-->
<camera>
<!--Name of the camera-->
<name>Equirectangular</name>
<!--Type of the camera-->
<type>4</type>
<!--Pixel ratio-->
<au>14.642254764</au>
<av>14.642254764</av>
<!--Principal point-->
<u0>46.0000000000</u0>
<v0>23.0000000000</v0>
</camera>
</root>
18 changes: 18 additions & 0 deletions config/calib_omni_46_46.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<root>
<!--M.I.S. Laboratory - Eynard Caron-->
<camera>
<!--Name of the camera-->
<name>Omni</name>
<!--Type of the camera-->
<type>0</type>
<!--Pixel ratio-->
<au>36.2253972</au>
<av>36.30754</av>
<!--Principal point-->
<u0>23.0863524</u0>
<v0>23.185494</v0>
<!--Xi-->
<xi>1.60230</xi>
</camera>
</root>
18 changes: 18 additions & 0 deletions config/calib_omni_80_64.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<root>
<!--PR team of the MIS lab - UPJV - France-->
<camera>
<!--Name of the camera-->
<name>Omni</name>
<!--Type of the camera-->
<type>0</type>
<!--Pixel ratio-->
<au>88.348125</au>
<av>88.348125</av>
<!--Principal point-->
<u0>40.0000000000</u0>
<v0>32.0000000000</v0>
<!--Xi-->
<xi>1.78412</xi>
</camera>
</root>
16 changes: 16 additions & 0 deletions config/calib_persp_320_256.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<root>
<!--PR team of the MIS lab - UPJV - France-->
<camera>
<!--Name of the camera-->
<name>Perspective</name>
<!--Type of the camera-->
<type>1</type>
<!--Pixel ratio-->
<au>377.358490566</au>
<av>377.358490566</av>
<!--Principal point-->
<u0>160.0000000000</u0>
<v0>128.0000000000</v0>
</camera>
</root>
16 changes: 16 additions & 0 deletions config/calib_persp_80_64.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<root>
<!--PR team of the MIS lab - UPJV - France-->
<camera>
<!--Name of the camera-->
<name>Perspective</name>
<!--Type of the camera-->
<type>1</type>
<!--Pixel ratio-->
<au>94.339622641</au>
<av>94.339622641</av>
<!--Principal point-->
<u0>40.0000000000</u0>
<v0>32.0000000000</v0>
</camera>
</root>
9 changes: 9 additions & 0 deletions config/insta360toUR10flange.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
rows: 6
cols: 1
data:
- [-0.15]
- [0.0]
- [-0.021]
- [1.2091]
- [1.2091]
- [-1.2091]
9 changes: 9 additions & 0 deletions config/insta360toUR5flange.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
rows: 6
cols: 1
data:
- [0.0]
- [0.0]
- [0.15]
- [-1.2091]
- [1.2091]
- [-1.2091]
126 changes: 126 additions & 0 deletions launch/pgmvsCaptureAndSaveDesired_FL3-U3_Fujinon_resize0p125.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
<launch>
<!-- Start the camera and settings -->
<!--
<include file="$(find spinnaker_camera_driver)/launch/camera.launch"/>
-->
<!-- Determine this using rosrun spinnaker_camera_driver list_cameras.
If not specified, defaults to first camera found. -->
<arg name="camera_name" default="camera" />
<arg name="camera_serial" default="0" />
<arg name="calibrated" default="0" />
<arg name="device_type" default="USB3" /> <!-- USB3 or GigE -->

<!-- When unspecified, the driver will use the default framerate as given by the
camera itself. Use the parameter 'control_frame_rate' to enable manual frame
rate control, and 'frame_rate' to set the frame rate value. -->
<arg name="control_frame_rate" default="True" />
<arg name="frame_rate" default="60" />

<!-- Disabling ISP will dramatically increase frame-rate. However, it can only be
disabled when using Bayer encoding (e.g. BayerRG8)-->
<arg name="isp_enable" default="False" />
<arg name="encoding" default="Mono8" />
<arg name="color_balance" default="Off" /> <!-- Off, Once, or Continuous -->
<!-- Available Encodings:
Mono: YUV: YCbCr: Other:
- Mono8 - YUV411Packed - YCbCr8 - BGR8
- Mono16 - YUV422Packed - YCbCr422_8 - BGRa8
- Mono12p - YUV444Packed - YCbCr411_8 - RGB8Packed
- Mono12Packed
Bayer:
- BayerGR8 - BayerGR12p
- BayerRG8 - BayerRG12p
- BayerGB8 - BayerGB12p
- BayerBG8 - BayerBG12p
- BayerGR16 - BayerGR12Packed
- BayerRG16 - BayerRG12Packed
- BayerGB16 - BayerGB12Packed
- BayerBG16 - BayerBG12Packed
-->

<arg name="exposure_auto" default="Off" /> <!-- Off, Once, or Continuous -->
<arg name="auto_gain" default="Off" /> <!-- Off, Once, or Continuous -->
<arg name="exposure_time" default="16000" /> <!-- micro seconds -->
<arg name="gain" default="0" /> <!-- -->
<arg name="black_level" default="0" /> <!-- -->
<arg name="black_level_auto" default="Off" /> <!-- -->

<group ns="$(arg camera_name)">
<!-- Nodelet manager -->
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" cwd="node" output="screen"/>
->
<!-- Camera nodelet -->
<node pkg="nodelet" type="nodelet" name="spinnaker_camera_nodelet"
args="load spinnaker_camera_driver/SpinnakerCameraNodelet camera_nodelet_manager" >

<param name="frame_id" value="$(arg camera_name)" />
<param name="serial" value="$(arg camera_serial)" />
<param name="device_type" value="$(arg device_type)" />

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

<!-- Image Processing -->
<param name="isp_enable" value="$(arg isp_enable)" />
<param name="auto_white_balance" value="$(arg color_balance)" />
<param name="image_format_color_coding" value="$(arg encoding)" />

<!-- Image Resolution -->
<!-- Height and width pixel size cannot be set directly. Instead use the
binning, offset, and region of interest options.
- RoI: range of pixels to select from original image
(Note: RoI is defined from image pixel origin (i.e. top left))
- Binning: reduces resolution by a factor of 1, 2, 4, or 8
- Offset: moves the pixel origin
x-offset = max_width/x_binning - roi_width/2
y-offset = max_height/y_binning - roi_height/2
-->

<param name="image_format_x_binning" value="2" />
<param name="image_format_y_binning" value="2" />
<!--
<param name="image_format_x_offset" value="128" />
<param name="image_format_y_offset" value="122" />
<param name="image_format_roi_width" value="1280" />
<param name="image_format_roi_height" value="720" />
-->

<param name="exposure_auto" value="$(arg exposure_auto)" />
<param name="auto_gain" value="$(arg auto_gain)" />
<param name="exposure_time" value="$(arg exposure_time)" />
<param name="gain" value="$(arg gain)" />
<param name="black_level" value="$(arg black_level)" />
<param name="black_level_auto" value="$(arg black_level_auto)" />

<!-- Use the camera_calibration package to create this file -->
<param name="camera_info_url" if="$(arg calibrated)"
value="file://$(env HOME)/.ros/camera_info/$(arg camera_serial).yaml" />
</node>

<!-- Debayering nodelet -->
<node pkg="nodelet" type="nodelet" name="image_proc_debayer"
args="load image_proc/debayer camera_nodelet_manager">
</node>
</group>

<!-- Resize the captured images to reduce the processing time -->
<node name="image_resize" pkg="nodelet" type="nodelet" args="standalone image_proc/resize">
<remap from="image" to="/camera/image_mono" />
<param name="scale_width" value="0.125" />
<param name="scale_height" value="0.125" />
</node>

<!-- Start the desired image saving node for photometric visual servoing -->
<node name="pgmvsCaptureAndSaveDesired" pkg="ros_dvs_bridge" type="ros_dvs_bridge_pgmvsCaptureAndSaveDesired"/> <!-- launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@' "> -->
<param name="cameraTopic" type="string" value="/image_resize/image"/>
<param name="logs" type="string" value="$(env HOME)/.ros/ros_dvs_bridge/"/>

<param name="rosbagForEVS" type="bool" value="true"/>
<param name="camera2tool" type="string" value="$(find ros_dvs_bridge)/config/FL3-U3toUR10flange.yml"/>
<param name="cameraPoseTopic" type="string" value="/tf"/>
<param name="desiredPoseTopicForEVS" type="string" value="/vs/camera/desired_pose"/>

</launch>

112 changes: 112 additions & 0 deletions launch/pgmvsCaptureAndSaveDesired_FL3-U3_resize0p125.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
<launch>
<!-- Start the camera and settings -->
<!--
<include file="$(find spinnaker_camera_driver)/launch/camera.launch"/>
-->
<!-- Determine this using rosrun spinnaker_camera_driver list_cameras.
If not specified, defaults to first camera found. -->
<arg name="camera_name" default="camera" />
<arg name="camera_serial" default="0" />
<arg name="calibrated" default="0" />
<arg name="device_type" default="USB3" /> <!-- USB3 or GigE -->

<!-- When unspecified, the driver will use the default framerate as given by the
camera itself. Use the parameter 'control_frame_rate' to enable manual frame
rate control, and 'frame_rate' to set the frame rate value. -->
<arg name="control_frame_rate" default="True" />
<arg name="frame_rate" default="60" />

<!-- Disabling ISP will dramatically increase frame-rate. However, it can only be
disabled when using Bayer encoding (e.g. BayerRG8)-->
<arg name="isp_enable" default="False" />
<arg name="encoding" default="Mono8" />
<arg name="color_balance" default="Off" /> <!-- Off, Once, or Continuous -->
<!-- Available Encodings:
Mono: YUV: YCbCr: Other:
- Mono8 - YUV411Packed - YCbCr8 - BGR8
- Mono16 - YUV422Packed - YCbCr422_8 - BGRa8
- Mono12p - YUV444Packed - YCbCr411_8 - RGB8Packed
- Mono12Packed
Bayer:
- BayerGR8 - BayerGR12p
- BayerRG8 - BayerRG12p
- BayerGB8 - BayerGB12p
- BayerBG8 - BayerBG12p
- BayerGR16 - BayerGR12Packed
- BayerRG16 - BayerRG12Packed
- BayerGB16 - BayerGB12Packed
- BayerBG16 - BayerBG12Packed
-->

<group ns="$(arg camera_name)">
<!-- Nodelet manager -->
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" cwd="node" output="screen"/>
->
<!-- Camera nodelet -->
<node pkg="nodelet" type="nodelet" name="spinnaker_camera_nodelet"
args="load spinnaker_camera_driver/SpinnakerCameraNodelet camera_nodelet_manager" >

<param name="frame_id" value="$(arg camera_name)" />
<param name="serial" value="$(arg camera_serial)" />
<param name="device_type" value="$(arg device_type)" />

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

<!-- Image Processing -->
<param name="isp_enable" value="$(arg isp_enable)" />
<param name="auto_white_balance" value="$(arg color_balance)" />
<param name="image_format_color_coding" value="$(arg encoding)" />

<!-- Image Resolution -->
<!-- Height and width pixel size cannot be set directly. Instead use the
binning, offset, and region of interest options.
- RoI: range of pixels to select from original image
(Note: RoI is defined from image pixel origin (i.e. top left))
- Binning: reduces resolution by a factor of 1, 2, 4, or 8
- Offset: moves the pixel origin
x-offset = max_width/x_binning - roi_width/2
y-offset = max_height/y_binning - roi_height/2
-->

<param name="image_format_x_binning" value="2" />
<param name="image_format_y_binning" value="2" />
<!--
<param name="image_format_x_offset" value="128" />
<param name="image_format_y_offset" value="122" />
<param name="image_format_roi_width" value="1280" />
<param name="image_format_roi_height" value="720" />
-->

<!-- Use the camera_calibration package to create this file -->
<param name="camera_info_url" if="$(arg calibrated)"
value="file://$(env HOME)/.ros/camera_info/$(arg camera_serial).yaml" />
</node>

<!-- Debayering nodelet -->
<node pkg="nodelet" type="nodelet" name="image_proc_debayer"
args="load image_proc/debayer camera_nodelet_manager">
</node>
</group>

<!-- Resize the captured images to reduce the processing time -->
<node name="image_resize" pkg="nodelet" type="nodelet" args="standalone image_proc/resize">
<remap from="image" to="/camera/image_mono" />
<param name="scale_width" value="0.125" />
<param name="scale_height" value="0.125" />
</node>

<!-- Start the desired image saving node for photometric visual servoing -->
<node name="pgmvsCaptureAndSaveDesired" pkg="ros_dvs_bridge" type="ros_dvs_bridge_pgmvsCaptureAndSaveDesired"/> <!-- launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@' "> -->
<param name="cameraTopic" type="string" value="/image_resize/image"/>
<param name="logs" type="string" value="$(env HOME)/.ros/ros_dvs_bridge/"/>

<param name="rosbagForEVS" type="bool" value="true"/>
<param name="camera2tool" type="string" value="$(find ros_dvs_bridge)/config/FL3-U3toUR10flange.yml"/>
<param name="cameraPoseTopic" type="string" value="/tf"/>
<param name="desiredPoseTopicForEVS" type="string" value="/vs/camera/desired_pose"/>

</launch>

Loading

0 comments on commit fd341a1

Please sign in to comment.