Skip to content

Commit f16e6c0

Browse files
authored
Feature/image flip (#41)
* Feature/cam info msg fix (#38) * minor changes to adding camerainfo header in export_to_ros method * will handle if binning is set properly and wwarn if camera is not calibrated at full resolution * Adding parameters for horizontal and vertical image flipping * will add feature to flip image horizontally and vertically, nodelet_subrciber_example.launch has been simplified * updated Readme to reflect flip horizontal and flip vertical params edits
1 parent 0261b67 commit f16e6c0

File tree

11 files changed

+90
-70
lines changed

11 files changed

+90
-70
lines changed

README.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,12 @@ All the parameters can be set via the launch file or via the yaml config_file.
9191
Flag whether each image should have Unique timestamps vs the master cams time stamp for all
9292
* ~max_rate_save (bool, default: false)
9393
Flag for max rate mode which is when the master triggers the slaves and saves images at maximum rate possible. This is the multithreaded mode
94+
* ~flip_horizontal (bool, default: false)
95+
Flag to flip image horizontally on camera itself, this is not a rotate only a mirror image. This setting does enumeration: "reverseX". It should be specified for all cameras or can be left unspecified for all cameras for default behaviour.
96+
* ~flip_vertical (bool, default: false)
97+
Flag to flip image vertically on camera itself, this is not a rotate only a mirror image. This setting does enumeration: "reverseY". It should be specified for all cameras or can be left unspecified for all cameras for default behaviour.
98+
99+
If both horizontal and vertical flags are true, then it is equivalent to rotating 180deg.
94100

95101
### node/nodelet Specific Parameters
96102
* ~tf_prefix (string, default: "")

include/spinnaker_sdk_camera_driver/capture.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,8 @@ namespace acquisition {
8787
vector<vector<double>> rect_coeff_vec_;
8888
vector<vector<double>> proj_coeff_vec_;
8989
vector<string> imageNames;
90+
vector<bool> flip_horizontal_vec_;
91+
vector<bool> flip_vertical_vec_;
9092

9193
string path_;
9294
string todays_date_;

launch/acquisition.launch

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
2121
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
2222
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
23-
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
23+
2424

2525
<!-- nodelet manager params-->
2626
<arg name="nodelet_manager_name" default="vision_nodelet_manager" doc="name of the nodelet manager, comes handy when launching multiple nodelets from different launch files" />
@@ -29,6 +29,8 @@
2929

3030
<!-- Capture nodelet params-->
3131
<arg name="tf_prefix" default="" doc="will prefix (arg tf_prefix)/ to existing frame_id in Image msg and camerainfo msg" />
32+
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
33+
3234
<!-- start the nodelet manager if $(arg start_nodelet_manager) is true-->
3335
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" if="$(arg start_nodelet_manager)" />
3436

launch/acquisition_node.launch

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,10 +21,11 @@
2121
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
2222
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
2323
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
24-
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
2524

2625
<!-- acquisiton node params-->
27-
<arg name="tf_prefix" default="" />
26+
<arg name="tf_prefix" default="" />
27+
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
28+
2829
<!-- load the acquisition node -->
2930

3031
<node pkg="spinnaker_sdk_camera_driver" type="acquisition_node" name="acquisition_node" output="$(arg output)" args="" respawn="false" >
Lines changed: 9 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -1,65 +1,12 @@
11
<launch>
2-
<!-- configure console output verbosity mode:debug_console.conf or std_console.conf -->
3-
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/std_console.conf"/>
4-
5-
<!-- acquisition spinnaker params-->
6-
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
7-
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
8-
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
9-
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
10-
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4, AutoExposureTargetGreyValueAuto will be set to continuous(auto) also available as dynamic reconfigurable parameter" />
11-
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
12-
<arg name="live" default="false" doc="Show images on screen GUI"/>
13-
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
14-
<arg name="output" default="screen" doc="display output to screen or log file"/>
15-
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
16-
<arg name="save_path" default="~" doc="location to save the image data"/>
17-
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
18-
<arg name="soft_framerate" default="30" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
19-
<arg name="time" default="false" doc="Show time/FPS on output"/>
20-
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
21-
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
22-
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
23-
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
24-
25-
<!-- nodelet manager params-->
26-
<arg name="nodelet_manager_name" default="vision_nodelet_manager" doc="name of the nodelet manager, comes handy when launching multiple nodelets from different launch files" />
27-
<arg name="start_nodelet_manager" default="false" doc="If set to True, creates a nodelet manager with $(arg nodelet_manager_name).
28-
If False, the acquisition/capture_nodelet waits for the nodelet_manager name $(arg nodelet_manager_name)" />
29-
30-
<!-- Capture nodelet params-->
31-
<arg name="tf_prefix" default="" doc="will prefix (arg tf_prefix)/ to existing frame_id in Image msg and camerainfo msg" />
32-
<!-- start the nodelet manager -->
33-
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" />
34-
35-
<!-- load the acquisition nodelet -->
36-
<node pkg="nodelet" type="nodelet" name="acquisition_node"
37-
args="load acquisition/capture_nodelet $(arg nodelet_manager_name)" >
38-
<!-- load the acquisition node parameters file. Note any parameters provided in this file will
39-
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
40-
<rosparam command="load" file="$(arg config_file)" />
41-
42-
<!-- Load parameters onto server using argument or default values above -->
43-
<param name="exposure_time" value="$(arg exposure_time)" />
44-
<param name="external_trigger" value="$(arg external_trigger)" />
45-
<param name="target_grey_value" value="$(arg target_grey_value)" />
46-
<param name="binning" value="$(arg binning)" />
47-
<param name="color" value="$(arg color)" />
48-
<param name="frames" value="$(arg frames)" />
49-
<param name="live" value="$(arg live)" />
50-
<param name="live_grid" value="$(arg live_grid)" />
51-
<param name="save" value="$(arg save)" />
52-
<param name="save_type" value="$(arg save_type)" />
53-
<param name="save_path" value="$(arg save_path)" />
54-
<param name="soft_framerate" value="$(arg soft_framerate)" />
55-
<param name="time" value="$(arg time)" />
56-
<param name="utstamps" value="$(arg utstamps)" />
57-
<param name="to_ros" value="$(arg to_ros)"/>
58-
<param name="max_rate_save" value="$(arg max_rate_save)"/>
59-
<param name="tf_prefix" value="$(arg tf_prefix)" />
60-
61-
</node>
62-
2+
<arg name="vision_nm" default="vision_nodelet_manager_example" doc="name of the nodelet manager" />
3+
<arg name="camera_tf_prefix" default="" />
4+
5+
<include file="$(find spinnaker_sdk_camera_driver)/launch/acquisition.launch" >
6+
<arg name="nodelet_manager_name" value="$(arg vision_nm)" />
7+
<arg name="tf_prefix" value="$(arg camera_tf_prefix)" />
8+
</include>
9+
6310
<node pkg="nodelet" type="nodelet" name="subscriber_nodelet"
64-
args="load acquisition/subscriber_nodelet $(arg nodelet_manager_name)" output="screen" />
11+
args="load acquisition/subscriber_nodelet $(arg vision_nm)" output="screen" />
6512
</launch>

params/external_trigger_params.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,12 @@ cam_aliases:
55
skip: 20
66
delay: 1.0
77

8+
flip_horizontal:
9+
- false
10+
11+
flip_vertical:
12+
- false
13+
814
# Assign all the follwing via launch file to prevent confusion and conflict
915

1016
#save_path: ~/projects/data

params/multi-cam_example.yaml

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,3 +52,16 @@ projection_coeffs:
5252
- [923.700443, 0.000000, 973.847232, 0.000000, 0.000000, 1100.763631, 832.341983, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
5353
- [800.784635, 0.000000, 983.78252, 0.000000, 0.000000, 903.736234, 798.561973, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
5454

55+
flip_horizontal:
56+
- false
57+
- false
58+
- false
59+
- false
60+
- false
61+
62+
flip_vertical:
63+
- false
64+
- false
65+
- false
66+
- false
67+
- false

params/stereo_camera_example.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,3 +40,11 @@ rectification_coeffs:
4040
projection_coeffs:
4141
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
4242
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
43+
44+
flip_horizontal:
45+
- false
46+
- false
47+
48+
flip_vertical:
49+
- false
50+
- false

params/test_params.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,3 +34,9 @@ rectification_coeffs:
3434

3535
projection_coeffs:
3636
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
37+
38+
flip_horizontal:
39+
- false
40+
41+
flip_vertical:
42+
- false

src/camera.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -184,8 +184,7 @@ void acquisition::Camera::setBoolValue(string setting, bool val) {
184184
if (!IsAvailable(ptr) || !IsWritable(ptr)) {
185185
ROS_FATAL_STREAM("Unable to set " << setting << " to " << val << " (ptr retrieval). Aborting...");
186186
}
187-
if (val) ptr->SetValue("True");
188-
else ptr->SetValue("False");
187+
ptr->SetValue(val);
189188

190189
ROS_DEBUG_STREAM(setting << " set to " << val);
191190

0 commit comments

Comments
 (0)