Skip to content
This repository has been archived by the owner on Aug 1, 2019. It is now read-only.

Commit

Permalink
Fix image_geometry tests.
Browse files Browse the repository at this point in the history
Similar to the last commit, CameraInfo objects don't get fully
initialized to 0 (or default) when constructing.  Thus, make
sure we fill in all fields of a CameraInfo object before passing
it down into PinholeCameraModel.  Also, make another test
use this initialized version of the object, instead of a quite
new one.

Signed-off-by: Chris Lalancette <clalancette@osrfoundation.org>
  • Loading branch information
clalancette committed Apr 21, 2017
1 parent d2e5edb commit ecbcd64
Showing 1 changed file with 15 additions and 10 deletions.
25 changes: 15 additions & 10 deletions image_geometry/test/utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,16 +26,27 @@ class PinholeTest : public testing::Test
0.0, 295.53402059708782, 223.29617881774902, 0.0,
0.0, 0.0, 1.0, 0.0};


cam_info_.header.stamp.sec = 0;
cam_info_.header.stamp.nanosec = 0;
cam_info_.header.frame_id = "tf_frame";
cam_info_.height = 480;
cam_info_.width = 640;
cam_info_.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
// No binning
cam_info_.binning_x = 0;
cam_info_.binning_y = 0;
// No ROI
cam_info_.roi.x_offset = 0;
cam_info_.roi.y_offset = 0;
cam_info_.roi.height = 0;
cam_info_.roi.width = 0;
cam_info_.roi.do_rectify = false;
cam_info_.d.resize(5);
std::copy(D, D+5, cam_info_.d.begin());
std::copy(K, K+9, cam_info_.k.begin());
std::copy(R, R+9, cam_info_.r.begin());
std::copy(P, P+12, cam_info_.p.begin());
cam_info_.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;

model_.fromCameraInfo(cam_info_);
}
Expand Down Expand Up @@ -150,15 +161,9 @@ TEST_F(PinholeTest, getDeltas)

TEST_F(PinholeTest, initialization)
{

sensor_msgs::msg::CameraInfo info;
image_geometry::PinholeCameraModel camera;

camera.fromCameraInfo(info);

EXPECT_EQ(camera.initialized(), 1);
EXPECT_EQ(camera.projectionMatrix().rows, 3);
EXPECT_EQ(camera.projectionMatrix().cols, 4);
EXPECT_EQ(model_.initialized(), 1);
EXPECT_EQ(model_.projectionMatrix().rows, 3);
EXPECT_EQ(model_.projectionMatrix().cols, 4);
}

TEST_F(PinholeTest, rectifyIfCalibrated)
Expand Down

0 comments on commit ecbcd64

Please sign in to comment.