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

Commit

Permalink
Remove use of boost from image_geometry.
Browse files Browse the repository at this point in the history
This has also been proposed in upstream ros-perception/vision_opencv
for ROS1.

Signed-off-by: Chris Lalancette <clalancette@osrfoundation.org>
  • Loading branch information
clalancette committed Apr 21, 2017
1 parent 2b95db1 commit b34ff41
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 5 deletions.
3 changes: 1 addition & 2 deletions image_geometry/include/image_geometry/pinhole_camera_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <boost/shared_ptr.hpp>
#include <stdexcept>

namespace image_geometry {
Expand Down Expand Up @@ -271,7 +270,7 @@ class PinholeCameraModel

// Use PIMPL here so we can change internals in patch updates if needed
struct Cache;
boost::shared_ptr<Cache> cache_; // Holds cached data for internal use
std::shared_ptr<Cache> cache_; // Holds cached data for internal use

void initRectificationMaps() const;

Expand Down
5 changes: 2 additions & 3 deletions image_geometry/src/pinhole_camera_model.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#include "image_geometry/pinhole_camera_model.h"
#include <sensor_msgs/distortion_models.hpp>
#include <boost/make_shared.hpp>

namespace image_geometry {

Expand Down Expand Up @@ -56,7 +55,7 @@ bool update(const T& new_val, T& my_val)
return true;
}

// For boost::array, std::vector
// For std::array, std::vector
template<typename MatT>
bool updateMat(const MatT& new_mat, MatT& my_mat, cv::Mat_<double>& cv_mat, int rows, int cols)
{
Expand All @@ -83,7 +82,7 @@ bool PinholeCameraModel::fromCameraInfo(const sensor_msgs::msg::CameraInfo& msg)
{
// Create our repository of cached data (rectification maps, etc.)
if (!cache_)
cache_ = boost::make_shared<Cache>();
cache_ = std::make_shared<Cache>();

// Binning = 0 is considered the same as binning = 1 (no binning).
uint32_t binning_x = msg.binning_x ? msg.binning_x : 1;
Expand Down

0 comments on commit b34ff41

Please sign in to comment.