undistort_depth.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <ros/ros.h>
00029 #include <pluginlib/class_list_macros.h>
00030 #include <nodelet/nodelet.h>
00031 
00032 #include <sensor_msgs/Image.h>
00033 #include <sensor_msgs/image_encodings.h>
00034 
00035 #include <image_transport/image_transport.h>
00036 #include <image_transport/subscriber.h>
00037 #include <image_transport/publisher.h>
00038 
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <opencv2/highgui/highgui.hpp>
00041 
00042 #include "rtabmap/core/clams/discrete_depth_distortion_model.h"
00043 #include "rtabmap/utilite/UConversion.h"
00044 
00045 namespace rtabmap_ros
00046 {
00047 
00048 class UndistortDepth : public nodelet::Nodelet
00049 {
00050 public:
00051         UndistortDepth()
00052         {}
00053 
00054         virtual ~UndistortDepth()
00055         {
00056         }
00057 
00058 private:
00059         virtual void onInit()
00060         {
00061                 ros::NodeHandle & nh = getNodeHandle();
00062                 ros::NodeHandle & pnh = getPrivateNodeHandle();
00063 
00064                 std::string modelPath;
00065                 pnh.param("model", modelPath, modelPath);
00066 
00067                 if(modelPath.empty())
00068                 {
00069                         NODELET_ERROR("undistort_depth: \"model\" parameter should be set!");
00070                 }
00071 
00072                 model_.load(modelPath);
00073                 if(!model_.isValid())
00074                 {
00075                         NODELET_ERROR("Loaded distortion model from \"%s\" is not valid!", modelPath.c_str());
00076                 }
00077                 else
00078                 {
00079                         image_transport::ImageTransport it(nh);
00080                         sub_ = it.subscribe("depth", 1, &UndistortDepth::callback, this);
00081                         pub_ = it.advertise(uFormat("%s_undistorted", nh.resolveName("depth").c_str()), 1);
00082                 }
00083         }
00084 
00085         void callback(const sensor_msgs::ImageConstPtr& depth)
00086         {
00087                 if(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)!=0 &&
00088                    depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)!=0 &&
00089                    depth->encoding.compare(sensor_msgs::image_encodings::MONO16)!=0)
00090                 {
00091                         NODELET_ERROR("Input type depth=32FC1,16UC1,MONO16");
00092                         return;
00093                 }
00094 
00095                 if(pub_.getNumSubscribers())
00096                 {
00097                         if(depth->width == model_.getWidth() && depth->width == model_.getWidth())
00098                         {
00099                                 cv_bridge::CvImagePtr imageDepthPtr = cv_bridge::toCvCopy(depth);
00100                                 model_.undistort(imageDepthPtr->image);
00101                                 pub_.publish(imageDepthPtr->toImageMsg());
00102                         }
00103                         else
00104                         {
00105                                 NODELET_ERROR("Input depth image size (%dx%d) and distortion model "
00106                                                 "size (%dx%d) don't match! Cannot undistort image.",
00107                                                 depth->width, depth->height,
00108                                                 model_.getWidth(), model_.getHeight());
00109                         }
00110                 }
00111         }
00112 
00113 private:
00114         clams::DiscreteDepthDistortionModel model_;
00115         image_transport::Publisher pub_;
00116         image_transport::Subscriber sub_;
00117 };
00118 
00119 PLUGINLIB_EXPORT_CLASS(rtabmap_ros::UndistortDepth, nodelet::Nodelet);
00120 }
00121 


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49