Skip to content

Commit a903b0b

Browse files
authored
fixes issue when more cameras are plugged into host than count of specified cam_ids, node will not die, and now node publishes empty intrinsics in camerainfo msg when not provided, a bug from pr #33 where default was to not publish info msg (#36)
fixes issue when more cameras are plugged into host than count of specified cam_ids, node will not die, and now node publishes empty intrinsics in camerainfo msg when not provided, a bug from pr #33 where default was to not publish info msg (#36)
1 parent d1b34eb commit a903b0b

File tree

3 files changed

+76
-23
lines changed

3 files changed

+76
-23
lines changed

params/stereo_camera_example.yaml

+42
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
cam_ids:
2+
- 17197559
3+
- 17197547
4+
cam_aliases:
5+
- cam0
6+
- cam1
7+
master_cam: 17197559
8+
skip: 20
9+
delay: 1.0
10+
11+
# Assign all the follwing via launch file to prevent confusion and conflict
12+
13+
#save_path: ~/projects/data
14+
#save_type: .bmp #binary or .tiff or .bmp
15+
#binning: 1 # going from 2 to 1 requires cameras to be unplugged and replugged
16+
#color: false
17+
#frames: 50
18+
#soft_framerate: 20 # this frame rate reflects to the software frame rate set using ros::rate
19+
#exp: 997
20+
#to_ros: true #When to_ros is not selected, but live is selected, pressing 'space' exports single image to ROS
21+
22+
#Camera info message details
23+
distortion_model: plumb_bob
24+
image_height: 1536
25+
image_width: 2048
26+
distortion_coeffs:
27+
- [-0.021141875266089592, -0.3733872931278025, 2.385982550579459, 3.2824571732099725]
28+
- [-0.021141875266089592, -0.3733872931278025, 2.385982550579459, 3.2824571732099725]
29+
30+
31+
#specified as [fx 0 cx 0 fy cy 0 0 1]
32+
intrinsic_coeffs:
33+
- [1886.9232141485886, 0.0, 604.7214878709341, 0.0, 1886.6668765711668, 493.47726714719823, 0.0, 0.0, 1.0]
34+
- [1886.9232141485886, 0.0, 604.7214878709341, 0.0, 1886.6668765711668, 493.47726714719823, 0.0, 0.0, 1.0]
35+
36+
rectification_coeffs:
37+
- [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
38+
- [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
39+
40+
projection_coeffs:
41+
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
42+
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]

params/test_params.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
cam_ids:
2-
- 18080155
2+
- 17197559
33
cam_aliases:
44
- cam0
5-
master_cam: 18080155
5+
master_cam: 17197559
66
skip: 20
77
delay: 1.0
88

src/capture.cpp

+32-21
Original file line numberDiff line numberDiff line change
@@ -251,24 +251,30 @@ void acquisition::Capture::load_cameras() {
251251
//camera_info_pubs.push_back(nh_.advertise<sensor_msgs::CameraInfo>("camera_array/"+cam_names_[j]+"/camera_info", 1));
252252

253253
img_msgs.push_back(sensor_msgs::ImagePtr());
254+
255+
sensor_msgs::CameraInfoPtr ci_msg(new sensor_msgs::CameraInfo());
256+
int image_width = 0;
257+
int image_height = 0;
258+
std::string distortion_model = "";
259+
nh_pvt_.getParam("image_height", image_height);
260+
nh_pvt_.getParam("image_width", image_width);
261+
nh_pvt_.getParam("distortion_model", distortion_model);
262+
ci_msg->header.frame_id = "cam_"+to_string(j)+"_optical_frame";
263+
// full resolution image_size
264+
ci_msg->height = image_height;
265+
ci_msg->width = image_width;
266+
// distortion
267+
ci_msg->distortion_model = distortion_model;
268+
// binning
269+
ci_msg->binning_x = binning_;
270+
ci_msg->binning_y = binning_;
271+
254272
if (PUBLISH_CAM_INFO_){
255-
sensor_msgs::CameraInfoPtr ci_msg(new sensor_msgs::CameraInfo());
256-
int image_width = 0;
257-
int image_height = 0;
258-
std::string distortion_model = "";
259-
nh_pvt_.getParam("image_height", image_height);
260-
nh_pvt_.getParam("image_width", image_width);
261-
nh_pvt_.getParam("distortion_model", distortion_model);
262-
ci_msg->header.frame_id = "cam_"+to_string(j)+"_optical_frame";
263-
// full resolution image_size
264-
ci_msg->height = image_height;
265-
ci_msg->width = image_width;
266-
// distortion
267-
ci_msg->distortion_model = distortion_model;
268273
ci_msg->D = distortion_coeff_vec_[j];
269274
// intrinsic coefficients
270-
for (int count = 0; count<intrinsic_coeff_vec_[j].size();count++)
275+
for (int count = 0; count<intrinsic_coeff_vec_[j].size();count++){
271276
ci_msg->K[count] = intrinsic_coeff_vec_[j][count];
277+
}
272278
// Rectification matrix
273279
if (!rect_coeff_vec_.empty())
274280
ci_msg->R = {
@@ -287,7 +293,8 @@ void acquisition::Capture::load_cameras() {
287293
proj_coeff_vec_[j][8], proj_coeff_vec_[j][9],
288294
proj_coeff_vec_[j][10], proj_coeff_vec_[j][11]};
289295
}
290-
else if(numCameras_ == 1){
296+
//else if(numCameras_ == 1){
297+
else if(cam_ids_.size() == 1){
291298
// for case of monocular camera, P[1:3,1:3]=K
292299
ci_msg->P = {
293300
intrinsic_coeff_vec_[j][0], intrinsic_coeff_vec_[j][1],
@@ -297,19 +304,23 @@ void acquisition::Capture::load_cameras() {
297304
intrinsic_coeff_vec_[j][6], intrinsic_coeff_vec_[j][7],
298305
intrinsic_coeff_vec_[j][8], 0};
299306
}
300-
// binning
301-
ci_msg->binning_x = binning_;
302-
ci_msg->binning_y = binning_;
303-
304-
cam_info_msgs.push_back(ci_msg);
305307
}
308+
309+
cam_info_msgs.push_back(ci_msg);
310+
306311
cam_counter++;
312+
307313
}
308314
}
309315
if (!current_cam_found) ROS_WARN_STREAM(" Camera "<<cam_ids_[j]<<" not detected!!!");
310316
}
311317
ROS_ASSERT_MSG(cams.size(),"None of the connected cameras are in the config list!");
312318
ROS_ASSERT_MSG(master_set,"The camera supposed to be the master isn't connected!");
319+
// Setting numCameras_ variable to reflect number of camera objects used.
320+
// numCameras_ variable is used in other methods where it means size of cams list.
321+
numCameras_ = cams.size();
322+
// setting PUBLISH_CAM_INFO_ to true so export to ros method can publish it_.advertiseCamera msg with zero intrisics and distortion coeffs.
323+
PUBLISH_CAM_INFO_ = true;
313324
}
314325

315326

@@ -558,7 +569,7 @@ void acquisition::Capture::read_parameters() {
558569
if (PUBLISH_CAM_INFO_)
559570
ROS_INFO(" Camera coeffs provided, camera info messges will be published.");
560571
else
561-
ROS_INFO(" Camera coeffs not provided correctly, camera info messges will not be published.");
572+
ROS_WARN(" Camera coeffs not provided correctly, camera info messges intrinsics and distortion coeffs will be published with zeros.");
562573

563574
// ROS_ASSERT_MSG(my_list.getType()
564575
// int num_ids = cam_id_vec.size();

0 commit comments

Comments
 (0)