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

Commit

Permalink
Make sure to properly initialize the CameraInfo structure.
Browse files Browse the repository at this point in the history
sensor_msgs::msg::CameraInfo is one of the common_interfaces
generated messages.  As such, it has a default constructor
that is empty and does no initialization.  This is important
to note, because it means that constructs such as:

class Foo
{
  protected:
    sensor_msgs::msg::CameraInfo cam_info_{};
};

Will *not* initialize all member variables of CameraInfo objects
to their default.  Thus, the PinholeCameraModel tests were
failing randomly because they were using random stack data for
their cam_info_ state.  Rectify this in PinholeCameraModel by
explicitly filling in all zeros for the CameraInfo objects.

Signed-off-by: Chris Lalancette <clalancette@osrfoundation.org>
  • Loading branch information
clalancette committed Apr 21, 2017
1 parent b34ff41 commit d2e5edb
Showing 1 changed file with 17 additions and 0 deletions.
17 changes: 17 additions & 0 deletions image_geometry/src/pinhole_camera_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,23 @@ struct PinholeCameraModel::Cache

PinholeCameraModel::PinholeCameraModel()
{
cam_info_.header.stamp.sec = 0;
cam_info_.header.stamp.nanosec = 0;
cam_info_.header.frame_id = "";
cam_info_.height = 0;
cam_info_.width = 0;
cam_info_.distortion_model = "";
std::fill(cam_info_.d.begin(), cam_info_.d.end(), 0);
std::fill(cam_info_.k.begin(), cam_info_.k.end(), 0);
std::fill(cam_info_.r.begin(), cam_info_.r.end(), 0);
std::fill(cam_info_.p.begin(), cam_info_.p.end(), 0);
cam_info_.binning_x = 0;
cam_info_.binning_y = 0;
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;
}

PinholeCameraModel& PinholeCameraModel::operator=(const PinholeCameraModel& other)
Expand Down

0 comments on commit d2e5edb

Please sign in to comment.