Skip to content

Commit a5966ab

Browse files
committed
changed dynamic reconfig levels
1 parent 302c8d4 commit a5966ab

File tree

5 files changed

+44
-48
lines changed

5 files changed

+44
-48
lines changed

cfg/spinnaker_cam.cfg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ gen = ParameterGenerator()
77

88

99
gen.add("target_grey_val", double_t, 1, "Set Target Grey Value", 50, 4, 90)
10-
gen.add("exposure_time", int_t, 3, "Set Exposure time (0:auto)", 0, 0, 15000)
10+
gen.add("exposure_time", int_t, 2, "Set Exposure time (0:auto)", 0, 0, 15000)
1111

1212

1313
exit(gen.generate(PACKAGE, "spinnaker_sdk_camera_driver", "spinnaker_cam"))

launch/acquisition.launch

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -1,31 +1,31 @@
11
<launch>
22
<!-- 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"/>
3+
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/debug_console.conf"/>
44

55
<!-- acquisition.lauynch -->
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="exp" default="0" doc="Exposure setting for cameras"/>
9-
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
10-
<arg name="live" default="false" doc="Show images on screen GUI"/>
11-
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
12-
<arg name="output" default="screen" doc="display output to screen or log file"/>
13-
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
14-
<arg name="save_path" default="~" doc="location to save the image data"/>
15-
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
16-
<arg name="soft_framerate" default="20" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
17-
<arg name="time" default="false" doc="Show time/FPS on output"/>
18-
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
19-
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
20-
<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" />
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="exp" default="0" doc="Exposure setting for cameras"/>
9+
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
10+
<arg name="live" default="false" doc="Show images on screen GUI"/>
11+
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
12+
<arg name="output" default="screen" doc="display output to screen or log file"/>
13+
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
14+
<arg name="save_path" default="~" doc="location to save the image data"/>
15+
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
16+
<arg name="soft_framerate" default="15" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
17+
<arg name="time" default="false" doc="Show time/FPS on output"/>
18+
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
19+
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
20+
<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" />
2121
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
2222

2323
<!-- load the acquisition node -->
2424
<node pkg="spinnaker_sdk_camera_driver" type="acquisition_node" name="acquisition_node" output="$(arg output)"
25-
args="">
25+
args="">
2626

2727
<!-- load the acquisition node parameters file. Note any parameters provided in this file will
28-
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
28+
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
2929
<rosparam command="load" file="$(arg config_file)" />
3030

3131
<!-- Load parameters onto server using argument or default values above -->
@@ -47,4 +47,4 @@
4747

4848
</node>
4949

50-
</launch>
50+
</launch>

params/test_params.yaml

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,8 @@
11
cam_ids:
2-
- 17197559
3-
- 17197547
2+
- 17197557
43
cam_aliases:
54
- cam0
6-
- cam1
7-
master_cam: 17197559
5+
master_cam: 17197557
86
skip: 20
97
delay: 1.0
108

@@ -23,8 +21,8 @@ delay: 1.0
2321
distortion_model: plumb_bob
2422
distortion_coeffs:
2523
- [-0.021141875266089592, -0.3733872931278025, 2.385982550579459, 3.2824571732099725]
26-
- [-0.021141875266089592, -0.3733872931278025, 2.385982550579459, 3.2824571732099725]
24+
#- [-0.021141875266089592, -0.3733872931278025, 2.385982550579459, 3.2824571732099725]
2725
#specified as [fx 0 cx 0 fy cy 0 0 1]
2826
intrinsic_coeffs:
2927
- [1886.9232141485886, 0.0, 604.7214878709341, 0.0, 1886.6668765711668, 493.47726714719823, 0.0, 0.0, 1.0]
30-
- [1886.9232141485886, 0.0, 604.7214878709341, 0.0, 1886.6668765711668, 493.47726714719823, 0.0, 0.0, 1.0]
28+
#- [1886.9232141485886, 0.0, 604.7214878709341, 0.0, 1886.6668765711668, 493.47726714719823, 0.0, 0.0, 1.0]

src/camera.cpp

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,8 @@ void acquisition::Camera::deinit() {
4040
ImagePtr acquisition::Camera::grab_frame() {
4141

4242
ImagePtr pResultImage = pCam_->GetNextImage(GET_NEXT_IMAGE_TIMEOUT_);
43-
4443
// Check if the Image is complete
44+
4545
if (pResultImage->IsIncomplete()) {
4646

4747
ROS_WARN_STREAM("Image incomplete with image status " << pResultImage->GetImageStatus() << "!");
@@ -60,11 +60,9 @@ ImagePtr acquisition::Camera::grab_frame() {
6060
}
6161

6262
}
63-
63+
6464
ROS_DEBUG_STREAM("Grabbed frame from camera " << get_id() << " with timestamp " << timestamp_*1000);
65-
66-
return pResultImage;
67-
65+
return pResultImage;
6866
}
6967

7068
// Returns last timestamp
@@ -96,19 +94,16 @@ Mat acquisition::Camera::convert_to_mat(ImagePtr pImage) {
9694
convertedImage = pImage->Convert(PixelFormat_BGR8); //, NEAREST_NEIGHBOR);
9795
else
9896
convertedImage = pImage->Convert(PixelFormat_Mono8); //, NEAREST_NEIGHBOR);
99-
10097
unsigned int XPadding = convertedImage->GetXPadding();
10198
unsigned int YPadding = convertedImage->GetYPadding();
10299
unsigned int rowsize = convertedImage->GetWidth();
103100
unsigned int colsize = convertedImage->GetHeight();
104-
105101
//image data contains padding. When allocating Mat container size, you need to account for the X,Y image data padding.
106102
Mat img;
107103
if (COLOR_)
108104
img = Mat(colsize + YPadding, rowsize + XPadding, CV_8UC3, convertedImage->GetData(), convertedImage->GetStride());
109105
else
110106
img = Mat(colsize + YPadding, rowsize + XPadding, CV_8UC1, convertedImage->GetData(), convertedImage->GetStride());
111-
112107
return img.clone();
113108
// return img;
114109

@@ -323,4 +318,4 @@ void acquisition::Camera::exposureTest() {
323318
float expTime=ptrExpTest->GetValue();
324319
ROS_DEBUG_STREAM("Exposure Time: "<<expTime<<endl);
325320

326-
}
321+
}

src/capture.cpp

Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -612,7 +612,7 @@ void acquisition::Capture::export_to_ROS() {
612612
cam_info_msgs[i]->header.stamp = mesg.header.stamp;
613613
}
614614
camera_image_pubs[i].publish(img_msgs[i],cam_info_msgs[i]);
615-
/*
615+
/*
616616
if (PUBLISH_CAM_INFO_){
617617
cam_info_msgs[i].header.stamp = mesg.header.stamp;
618618
camera_info_pubs[i].publish(cam_info_msgs[i]);
@@ -673,9 +673,9 @@ void acquisition::Capture::get_mat_images() {
673673

674674

675675
for (int i=0; i<numCameras_; i++) {
676-
676+
//ROS_INFO_STREAM("CAM ID IS "<< i);
677677
frames_[i] = cams[i].grab_mat_frame();
678-
678+
//ROS_INFO("sucess");
679679
time_stamps_[i] = cams[i].get_time_stamp();
680680

681681

@@ -724,7 +724,6 @@ void acquisition::Capture::run_soft_trig() {
724724
}
725725

726726
ros::Rate ros_rate(soft_framerate_);
727-
728727
try{
729728
while( ros::ok() ) {
730729

@@ -1020,18 +1019,22 @@ std::string acquisition::Capture::todays_date()
10201019
}
10211020

10221021
void acquisition::Capture::dynamicReconfigureCallback(spinnaker_sdk_camera_driver::spinnaker_camConfig &config, uint32_t level){
1023-
ROS_INFO_STREAM("Dynamic Reconfigure: Target grey value : " << config.target_grey_val <<"Exposure "<<config.exposure_time);
10241022
ROS_INFO_STREAM("Dynamic Reconfigure: Level : " << level);
1025-
1026-
if(level == 1){
1023+
if(level == 1 || level ==3){
1024+
ROS_INFO_STREAM("Target grey value : " << config.target_grey_val);
10271025
cams[MASTER_CAM_].setEnumValue("AutoExposureTargetGreyValueAuto", "Off");
10281026
cams[MASTER_CAM_].setFloatValue("AutoExposureTargetGreyValue", config.target_grey_val);
10291027
}
1030-
else if (level == 3 && config.exposure_time > 0){
1031-
cams[MASTER_CAM_].setEnumValue("ExposureAuto", "Off");
1032-
cams[MASTER_CAM_].setEnumValue("ExposureMode", "Timed");
1033-
cams[MASTER_CAM_].setFloatValue("ExposureTime", config.exposure_time);
1028+
if (level == 2 || level ==3){
1029+
ROS_INFO_STREAM("Exposure "<<config.exposure_time);
1030+
if(config.exposure_time > 0){
1031+
cams[MASTER_CAM_].setEnumValue("ExposureAuto", "Off");
1032+
cams[MASTER_CAM_].setEnumValue("ExposureMode", "Timed");
1033+
cams[MASTER_CAM_].setFloatValue("ExposureTime", config.exposure_time);
1034+
}
1035+
else if(config.exposure_time ==0){
1036+
cams[MASTER_CAM_].setEnumValue("ExposureAuto", "Continuous");
1037+
cams[MASTER_CAM_].setEnumValue("ExposureMode", "Timed");
1038+
}
10341039
}
1035-
1036-
10371040
}

0 commit comments

Comments
 (0)