RGBDOdometryNode.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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 "OdometryROS.h"
00029 
00030 #include <message_filters/subscriber.h>
00031 #include <message_filters/time_synchronizer.h>
00032 #include <message_filters/sync_policies/approximate_time.h>
00033 
00034 #include <image_transport/image_transport.h>
00035 #include <image_transport/subscriber_filter.h>
00036 
00037 #include <image_geometry/stereo_camera_model.h>
00038 
00039 #include <sensor_msgs/Image.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <cv_bridge/cv_bridge.h>
00042 
00043 #include "rtabmap_ros/MsgConversion.h"
00044 
00045 #include <rtabmap/utilite/ULogger.h>
00046 
00047 using namespace rtabmap;
00048 
00049 class RGBDOdometry : public rtabmap_ros::OdometryROS
00050 {
00051 public:
00052         RGBDOdometry(int argc, char * argv[]) :
00053                 rtabmap_ros::OdometryROS(argc, argv),
00054                 sync_(0)
00055         {
00056                 ros::NodeHandle nh;
00057                 ros::NodeHandle pnh("~");
00058 
00059                 int queueSize = 5;
00060                 pnh.param("queue_size", queueSize, queueSize);
00061 
00062                 ros::NodeHandle rgb_nh(nh, "rgb");
00063                 ros::NodeHandle depth_nh(nh, "depth");
00064                 ros::NodeHandle rgb_pnh(pnh, "rgb");
00065                 ros::NodeHandle depth_pnh(pnh, "depth");
00066                 image_transport::ImageTransport rgb_it(rgb_nh);
00067                 image_transport::ImageTransport depth_it(depth_nh);
00068                 image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
00069                 image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
00070 
00071                 image_mono_sub_.subscribe(rgb_it, rgb_nh.resolveName("image"), 1, hintsRgb);
00072                 image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image"), 1, hintsDepth);
00073                 info_sub_.subscribe(rgb_nh, "camera_info", 1);
00074 
00075                 ROS_INFO("\n%s subscribed to:\n   %s,\n   %s,\n   %s",
00076                                 ros::this_node::getName().c_str(),
00077                                 image_mono_sub_.getTopic().c_str(),
00078                                 image_depth_sub_.getTopic().c_str(),
00079                                 info_sub_.getTopic().c_str());
00080 
00081                 sync_ = new message_filters::Synchronizer<MySyncPolicy>(MySyncPolicy(queueSize), image_mono_sub_, image_depth_sub_, info_sub_);
00082                 sync_->registerCallback(boost::bind(&RGBDOdometry::callback, this, _1, _2, _3));
00083         }
00084 
00085         ~RGBDOdometry()
00086         {
00087                 delete sync_;
00088         }
00089 
00090         void callback(const sensor_msgs::ImageConstPtr& image,
00091                         const sensor_msgs::ImageConstPtr& depth,
00092                         const sensor_msgs::CameraInfoConstPtr& cameraInfo)
00093         {
00094                 if(!this->isPaused())
00095                 {
00096                         if(!(image->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
00097                                  image->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
00098                                  image->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
00099                                  image->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0) ||
00100                            !(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)==0 ||
00101                                  depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0 ||
00102                                  depth->encoding.compare(sensor_msgs::image_encodings::MONO16)==0))
00103                         {
00104                                 ROS_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 (mono8 recommended) and image_depth=16UC1,32FC1,mono16");
00105                                 return;
00106                         }
00107                         else if(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0)
00108                         {
00109                                 static bool warned = false;
00110                                 if(!warned)
00111                                 {
00112                                         ROS_WARN("Input depth type is 32FC1, please use type 16UC1 or mono16 for depth. The depth images "
00113                                                          "will be processed anyway but with a conversion. This warning is only be printed once...");
00114                                         warned = true;
00115                                 }
00116                         }
00117 
00118                         tf::StampedTransform localTransform;
00119                         try
00120                         {
00121                                 if(this->waitForTransform())
00122                                 {
00123                                         if(!this->tfListener().waitForTransform(this->frameId(), image->header.frame_id, image->header.stamp, ros::Duration(1)))
00124                                         {
00125                                                 ROS_WARN("Could not get transform from %s to %s after 1 second!", this->frameId().c_str(), image->header.frame_id.c_str());
00126                                                 return;
00127                                         }
00128                                 }
00129                                 this->tfListener().lookupTransform(this->frameId(), image->header.frame_id, image->header.stamp, localTransform);
00130                         }
00131                         catch(tf::TransformException & ex)
00132                         {
00133                                 ROS_WARN("%s",ex.what());
00134                                 return;
00135                         }
00136 
00137                         if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
00138                         {
00139                                 image_geometry::PinholeCameraModel model;
00140                                 model.fromCameraInfo(*cameraInfo);
00141                                 float fx = model.fx();
00142                                 float fy = model.fy();
00143                                 float cx = model.cx();
00144                                 float cy = model.cy();
00145                                 cv_bridge::CvImageConstPtr ptrImage = cv_bridge::toCvShare(image, "mono8");
00146                                 cv_bridge::CvImageConstPtr ptrDepth = cv_bridge::toCvShare(depth);
00147 
00148                                 rtabmap::SensorData data(
00149                                                 ptrImage->image,
00150                                                 ptrDepth->image,
00151                                                 fx,
00152                                                 fy,
00153                                                 cx,
00154                                                 cy,
00155                                                 rtabmap_ros::transformFromTF(localTransform),
00156                                                 rtabmap::Transform(),
00157                                                 1.0f,
00158                                                 1.0f,
00159                                                 0,
00160                                                 rtabmap_ros::timestampFromROS(image->header.stamp));
00161 
00162                                 this->processData(data, image->header);
00163                         }
00164                 }
00165         }
00166 
00167 private:
00168         image_transport::SubscriberFilter image_mono_sub_;
00169         image_transport::SubscriberFilter image_depth_sub_;
00170         message_filters::Subscriber<sensor_msgs::CameraInfo> info_sub_;
00171         typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> MySyncPolicy;
00172         message_filters::Synchronizer<MySyncPolicy> * sync_;
00173 };
00174 
00175 int main(int argc, char *argv[])
00176 {
00177         ULogger::setType(ULogger::kTypeConsole);
00178         ULogger::setLevel(ULogger::kWarning);
00179         ros::init(argc, argv, "rgbd_odometry");
00180 
00181         RGBDOdometry odom(argc, argv);
00182         ros::spin();
00183         return 0;
00184 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:25