Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Camera_info is incorrectly published for Format7 image frames #36

Open
Lenskiy opened this issue May 11, 2014 · 15 comments
Open

Camera_info is incorrectly published for Format7 image frames #36

Lenskiy opened this issue May 11, 2014 · 15 comments

Comments

@Lenskiy
Copy link

Lenskiy commented May 11, 2014

There is a problem in the way camera1394 package publishes camera_info. It adds non zero ROI parameters, however it publishes already cropped image. OpenCV tries to crop ROI from the already cropped image.

$ ROS_NAMESPACE=stereo_sync rosrun stereo_image_proc stereo_image_proc

OpenCV Error: Assertion failed (0 <= roi.x && 0 <= roi.width && roi.x + roi.width <= m.cols && 0 <= roi.y && 0 <= roi.height && roi.y + roi.height <= m.rows) in Mat, file /Users/artemlenskiy/ros/hydro/src/opencv2/modules/core/src/matrix.cpp, line 323
OpenCV Error: Assertion failed (0 <= roi.x && 0 <= roi.width && roi.x + roi.width <= m.cols && 0 <= roi.y && 0 <= roi.height && roi.y + roi.height <= m.rows) in Mat, file /Users/artemlenskiy/ros/hydro/src/opencv2/modules/core/src/matrix.cpp, line 323
libc++abi.dylib: libc++abi.dylib: terminating with uncaught exception of type cv::Exception: /Users/artemlenskiy/ros/hydro/src/opencv2/modules/core/src/matrix.cpp:323: error: (-215) 0 <= roi.x && 0 <= roi.width && roi.x + roi.width <= m.cols && 0 <= roi.y && 0 <= roi.height && roi.y + roi.height <= m.rows in function Mat
terminating with uncaught exception of type cv::Exception: /Users/artemlenskiy/ros/hydro/src/opencv2/modules/core/src/matrix.cpp:323: error: (-215) 0 <= roi.x && 0 <= roi.width && roi.x + roi.width <= m.cols && 0 <= roi.y && 0 <= roi.height && roi.y + roi.height <= m.rows in function Mat

Originally the issue was posted here
ros-perception/image_pipeline#55 (comment)

@jack-oquin
Copy link
Member

The exception text provided does not tell me what went wrong. What device are you using, and which Format7 mode?

Please post the exact CameraInfo published by the driver, and exactly what you republished to work around the problem. In particular, how was do_rectify set?

This driver attempts to follow the recommendations of REP-0104. Those recommendations are quite complex and we may have misunderstood them.

@vrabaud: any interpretive assistance you can give would be most helpful.

@vrabaud
Copy link

vrabaud commented May 11, 2014

I believe it's all in the comments of ros-perception/image_pipeline#55 : the ROI and the image info do not match up: the ROI is filled as if the dimensions of the image were the original ones (i.e. the ones from camera_info) while the image has the dimensions of the cropped image.

@jack-oquin
Copy link
Member

That issue reported different information for some other camera, as best I can tell.

I really need the exact CameraInfo for this device, also the device's make, model and Format7 mode. Almost every camera handles Format7 differently. I can't imagine solving this problem without that kind of information.

Specifically, if the Image is being cropped to the specified ROI, that must be happening in the camera, not the driver. BTW, that is normally what people want when using these parameters.

@ktossell
Copy link

It looks like @LucidOne may have calibrated against an image stream that was binned or cropped. Camera1394 will accept a calibration that matches either the full frame or the ROI, and it will pass along the calibration's height and width in the CameraInfo messages. If a binned or ROI-based calibration is used, it will break downstream nodes that expect the cinfo.width/height values to describe the full frame.

https://github.com/ros-drivers/camera1394/blob/master/src/nodes/format7.cpp#L437

@Lenksiy, what are the dimensions in your calibration file? Do they match the ROI or the full frame?

@Lenskiy
Copy link
Author

Lenskiy commented May 12, 2014

My config yaml contains these parameters

  video_mode: format7_mode0
  frame_rate: 60
  binning_x: 1
  binning_y: 1
  roi_width:  1328 
  roi_height: 600
  y_offset: 128 
  format7_color_coding: mono8
...

and calibration file start with these lines

image_width: 1328
image_height: 600
...

@Lenskiy
Copy link
Author

Lenskiy commented May 12, 2014

@jack-oquin yes the camera crops it inside.

@LucidOne
Copy link

I think my problems are with the prosilica driver, but I'm on vacation at the moment so I can't actually check

@jack-oquin
Copy link
Member

@Lenskiy: please paste in one frame of your camera_info topic contents. You can use this command, or something similar depending on your actual topic name:

rostopic echo /camera/camera_info

We really need that information. If possible, please do the same with your modified camera_info topic.

I still don't know the exact make and model of camera you are using. Please post.

@Lenskiy
Copy link
Author

Lenskiy commented May 12, 2014

I should have done it in a first place. Will do it in a few hours, not at the computer with the cameras now.
The piece of code that allows avoiding the problem is this

void Sync_cameras::equalizeTimestampsAndSetRoiToZeroCB(const sensor_msgs::ImageConstPtr& imgl, const sensor_msgs::ImageConstPtr& imgr){
    if (have_first_both_info){
        sensor_msgs::Image sync_img_r = *imgr;

        sync_img_r.header.stamp = imgl->header.stamp;
        info_l.header.stamp = imgl->header.stamp;
        info_r.header.stamp = imgl->header.stamp;
       //////////////////////////////////////////
        info_l.roi.x_offset = 0;
        info_l.roi.y_offset = 0;
        info_r.roi.x_offset = 0;
        info_r.roi.y_offset = 0;
        ////////////////////////////////////////////
        pub_l.publish(imgl);
        pub_r.publish(sync_img_r);
        pub_info_l.publish(info_l);
        pub_info_r.publish(info_r);
    }
}

@jack-oquin
Copy link
Member

I suspect @ktossell is pointing us in the right direction.

I don't see any use cases in REP-0104, that are exactly like this. In cropped video mode, the height and width are full resolution. They do not match the ROI height and width. That use case recommends setting do_rectify False, so we really need to know the value of that variable. Maybe the driver is setting it True in this situation.

A good option is to see if your camera works correctly with the entire image calibrated, since that is clearly the recommended REP-0104 approach.

@jack-oquin
Copy link
Member

@Lenskiy: Any new information about this problem?

@wngreene
Copy link

I'm having this same problem. I have a Point Grey Firefly MV MTC and calibrated in Format7_Mode1 (cropped to 640x480, then binned to 320x240). Launch file:

<launch>

  <!-- Firefly MTC Stereo (Format7-Mode1 320x240 @ 120 Hz)-->
  <group ns="stereo" >

    <!-- left camera -->
    <node pkg="camera1394" type="camera1394_node" name="left_node" output="screen">
      <param name="guid" value="00b09d0100a01a9a" />
      <param name="use_ros_time" value="True" />
      <param name="video_mode" value="format7_mode1" />

      <!-- ROI width/height in UNBINNED pixels -->
      <param name="roi_width" value="640" />
      <param name="roi_height" value="480" />

      <!-- ROI x/y offset in UNBINNED pixels -->
      <param name="x_offset" value="56" />
      <param name="y_offset" value="0" />

      <param name="camera_info_url" 
             value="file://$(find simple_stereo)/cfg/2015.01.19_stereo_firefly_mtc_ros_320x240_left.yml"/>
      <remap from="camera" to="left" />
    </node>
...
  </group>
</launch>

I calibrated with this setting which produced the following YAML file:

image_width: 320
image_height: 240
camera_name: narrow_stereo/left
camera_matrix:
  rows: 3
  cols: 3
  data: [186.684368, 0, 185.178204, 0, 185.935135, 113.514201, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [-0.280265, 0.086241, -3.2e-05, -0.000334, 0]
rectification_matrix:
  rows: 3
  cols: 3
  data: [0.999979, -0.000403, -0.006536999999999999, 0.000398, 1, -0.000672, 0.006536999999999999, 0.00067, 0.9999779999999999]
projection_matrix:
  rows: 3
  cols: 4
  data: [174.012789, 0, 172.847595, 0, 0, 174.012789, 111.874925, 0, 0, 0, 1, 0]

Launching the driver with that calibration gives the following CameraInfo:

height: 240
width: 320
distortion_model: ''
D: []
K: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
R: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
P: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
binning_x: 2
binning_y: 2
roi: 
  x_offset: 56
  y_offset: 0
  height: 480
  width: 640
  do_rectify: False

The parameters do not get filled in and the following warning is produced:

[ WARN] [1421775566.996886679]: Calibrated image size (320x240) matches neither full Format7 size (752x480)) nor ROI size (640x480)

Reading REP-0104, it seems like one is only supposed to calibrate with the full size image and any cropping or binning should be noted (i.e. we should not pretend that the above camera is actually 320x240). Is that correct/documented anywhere?

@wngreene
Copy link

Update:
By calibrating with the full size image stream, but launching with an ROI/binning I was able to sidestep the OpenCV expception above.

do_rectify is set to True however, when it should be set to False (see use cases 3 and 5 in REP 0104). If I'm interpreting the REP correctly, the user should be able to set do_rectify manually, which doesn't seem supported right now.

@jack-oquin
Copy link
Member

Thanks for the detailed report, @boblob.

The driver currently sets do_rectify automatically depending on whether it thinks the ROI matches the calibrated size. That roiMatchesCalibration logic looks incorrect for your use case with binning applied. REP-0104 is confusing, and we find it difficult to test all the relevant use cases and devices. I don't think I have any test cameras that support the type of binning and ROI your Point Grey Firefly MV MTC does.

It would be good if we can come up with a patch for use with binning to fix that bug.

Your implicit suggestion that we add a do_rectify parameter to the driver is also a good one. I would like it to have three values: true, false and auto, so the current behavior would continue to be used, except when the driver gets it wrong and users need to override it.

Does that make sense to you, @boblob, @Lenskiy and @ktossell?

@wngreene
Copy link

That makes sense to me. I agree that REP-0104 is very confusing and after reading through it, it didn't seem like there was an easy way to automate the choice of do_rectify, even by checking the binning values as you suggest. For example, I don't see a way to automate the distinction between use cases 5 and 6, other than encoding that 640x480 is a special resolution where the user doesn't want rectification. I think having the user set do_rectify is the safest way to go, as long as REP-0104 is referenced in the documetation so people can figure out what they should be using.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

6 participants