diff --git a/include/image_undistort/camera_parameters.h b/include/image_undistort/camera_parameters.h index 2a77b8e..5a09ec6 100644 --- a/include/image_undistort/camera_parameters.h +++ b/include/image_undistort/camera_parameters.h @@ -172,7 +172,7 @@ class CameraParametersPair { // rectified images class StereoCameraParameters { public: - StereoCameraParameters(const double scale = 1.0); + StereoCameraParameters(const double scale = 1.0, const bool match_input = false); bool setInputCameraParameters(const ros::NodeHandle& nh, const std::string& camera_namespace, @@ -198,9 +198,10 @@ class StereoCameraParameters { bool valid(const CameraSide& side, const CameraIO& io) const; private: - bool generateRectificationParameters(); + bool generateRectificationParameters(void); double scale_; + double match_input_; CameraParametersPair first_; CameraParametersPair second_; }; diff --git a/include/image_undistort/stereo_undistort.h b/include/image_undistort/stereo_undistort.h index 7efa8ce..60508cc 100644 --- a/include/image_undistort/stereo_undistort.h +++ b/include/image_undistort/stereo_undistort.h @@ -28,6 +28,14 @@ constexpr int kQueueSize = 10; // true to load input cam_info from ros parameters, false to get it from a // cam_info topic constexpr bool kDefaultInputCameraInfoFromROSParams = true; +// source of output camera information, the options are as follows- +// "auto_generated": (default), automatically generated based on the input, the +// focal length is the average of fx and fy of the input, the center point is +// in the center of the image, R=I and only x-translation is preserved. +// Resolution is set to the largest area that contains no empty pixels. The +// size of the output can also be modified with the "scale" parameter +// "match_input": intrinsic values are taken from the input camera parameters +const std::string kDefaultOutputCameraInfoSource = "auto_generated"; // namespace to use when loading first camera parameters from ros params const std::string kDefaultFirstCameraNamespace = "first_camera"; // namespace to use when loading second camera parameters from ros params @@ -124,6 +132,11 @@ class StereoUndistort { // camera parameters std::shared_ptr stereo_camera_parameters_ptr_; + enum class OutputInfoSource { + AUTO_GENERATED, + MATCH_INPUT, + }; + // undistorters std::shared_ptr first_undistorter_ptr_; std::shared_ptr second_undistorter_ptr_; @@ -133,6 +146,7 @@ class StereoUndistort { int queue_size_; int process_every_nth_frame_; std::string output_image_type_; + OutputInfoSource output_camera_info_source_; bool publish_tf_; std::string first_output_frame_; std::string second_output_frame_; diff --git a/src/camera_parameters.cpp b/src/camera_parameters.cpp index 2d57795..d555f01 100644 --- a/src/camera_parameters.cpp +++ b/src/camera_parameters.cpp @@ -545,8 +545,8 @@ bool CameraParametersPair::operator!=(const CameraParametersPair& B) const { return !(*this == B); } -StereoCameraParameters::StereoCameraParameters(const double scale) - : scale_(scale){}; +StereoCameraParameters::StereoCameraParameters(const double scale, const bool match_input) + : scale_(scale), match_input_(match_input){}; bool StereoCameraParameters::setInputCameraParameters( const ros::NodeHandle& nh, const std::string& camera_namespace, @@ -628,7 +628,7 @@ bool StereoCameraParameters::valid(const CameraSide& side, } } -bool StereoCameraParameters::generateRectificationParameters() { +bool StereoCameraParameters::generateRectificationParameters(void) { if (first_.getInputPtr()->p().isApprox(second_.getInputPtr()->p())) { ROS_ERROR( "Stereo rectification cannot be performed on cameras with a baseline " @@ -661,11 +661,21 @@ bool StereoCameraParameters::generateRectificationParameters() { T.inverse() * second_.getInputPtr()->T(), second_.getInputPtr()->K(), second_.getInputPtr()->D(), second_.getInputPtr()->distortionModel()); - // set individual outputs - if (!first_.setOptimalOutputCameraParameters(scale_) || - !second_.setOptimalOutputCameraParameters(scale_)) { - ROS_ERROR("Automatic generation of stereo output parameters failed"); - return false; + + if (match_input_) { + if (!first_.setOutputFromInput(scale_) || + !second_.setOutputFromInput(scale_)) { + ROS_ERROR("Automatic generation of stereo output parameters failed"); + return false; + } + } + else { + // set individual outputs + if (!first_.setOptimalOutputCameraParameters(scale_) || + !second_.setOptimalOutputCameraParameters(scale_)) { + ROS_ERROR("Automatic generation of stereo output parameters failed"); + return false; + } } // grab most conservative values @@ -701,4 +711,4 @@ const CameraParametersPair& StereoCameraParameters::getFirst() const { const CameraParametersPair& StereoCameraParameters::getSecond() const { return second_; } -} // namespace image_undistort \ No newline at end of file +} // namespace image_undistort diff --git a/src/stereo_undistort.cpp b/src/stereo_undistort.cpp index 141b1f9..651ce96 100644 --- a/src/stereo_undistort.cpp +++ b/src/stereo_undistort.cpp @@ -33,6 +33,20 @@ StereoUndistort::StereoUndistort(const ros::NodeHandle& nh, nh_private_.param("rename_radtan_plumb_bob", rename_radtan_plumb_bob_, kDefaultRenameRadtanPlumbBob); + std::string output_camera_info_source_in; + nh_private_.param("output_camera_info_source", output_camera_info_source_in, + kDefaultOutputCameraInfoSource); + if (output_camera_info_source_in == "auto_generated") { + output_camera_info_source_ = OutputInfoSource::AUTO_GENERATED; + } else if (output_camera_info_source_in == "match_input") { + output_camera_info_source_ = OutputInfoSource::MATCH_INPUT; + } else { + ROS_ERROR( + "Invalid camera source given, valid options are auto_generated, " + "match_input. Defaulting to auto_generated"); + output_camera_info_source_ = OutputInfoSource::AUTO_GENERATED; + } + bool invert_T; nh_private_.param("invert_T", invert_T, kDefaultInvertT); @@ -46,7 +60,7 @@ StereoUndistort::StereoUndistort(const ros::NodeHandle& nh, nh_private_.param("scale", scale, kDefaultScale); stereo_camera_parameters_ptr_ = - std::make_shared(scale); + std::make_shared(scale, (output_camera_info_source_ == OutputInfoSource::MATCH_INPUT)); nh_private_.param("process_every_nth_frame", process_every_nth_frame_, kDefaultProcessEveryNthFrame);