stereo_odometry.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 "OdometryROS.h"
00029 #include "pluginlib/class_list_macros.h"
00030 #include "nodelet/nodelet.h"
00031 
00032 #include <message_filters/subscriber.h>
00033 #include <message_filters/time_synchronizer.h>
00034 #include <message_filters/sync_policies/approximate_time.h>
00035 
00036 #include <image_transport/image_transport.h>
00037 #include <image_transport/subscriber_filter.h>
00038 
00039 #include <sensor_msgs/Image.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 
00042 #include <image_geometry/stereo_camera_model.h>
00043 
00044 #include <cv_bridge/cv_bridge.h>
00045 
00046 #include "rtabmap_ros/MsgConversion.h"
00047 
00048 #include <rtabmap/utilite/ULogger.h>
00049 #include <rtabmap/utilite/UTimer.h>
00050 
00051 using namespace rtabmap;
00052 
00053 namespace rtabmap_ros
00054 {
00055 
00056 class StereoOdometry : public rtabmap_ros::OdometryROS
00057 {
00058 public:
00059         StereoOdometry() :
00060                 rtabmap_ros::OdometryROS(true),
00061                 approxSync_(0),
00062                 exactSync_(0),
00063                 queueSize_(5)
00064         {
00065         }
00066 
00067         virtual ~StereoOdometry()
00068         {
00069                 if(approxSync_)
00070                 {
00071                         delete approxSync_;
00072                 }
00073                 if(exactSync_)
00074                 {
00075                         delete exactSync_;
00076                 }
00077         }
00078 
00079 private:
00080         virtual void onOdomInit()
00081         {
00082                 ros::NodeHandle & nh = getNodeHandle();
00083                 ros::NodeHandle & pnh = getPrivateNodeHandle();
00084 
00085                 bool approxSync = false;
00086                 pnh.param("approx_sync", approxSync, approxSync);
00087                 pnh.param("queue_size", queueSize_, queueSize_);
00088                 NODELET_INFO("Approximate time sync = %s", approxSync?"true":"false");
00089 
00090                 ros::NodeHandle left_nh(nh, "left");
00091                 ros::NodeHandle right_nh(nh, "right");
00092                 ros::NodeHandle left_pnh(pnh, "left");
00093                 ros::NodeHandle right_pnh(pnh, "right");
00094                 image_transport::ImageTransport left_it(left_nh);
00095                 image_transport::ImageTransport right_it(right_nh);
00096                 image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
00097                 image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
00098 
00099                 imageRectLeft_.subscribe(left_it, left_nh.resolveName("image_rect"), 1, hintsLeft);
00100                 imageRectRight_.subscribe(right_it, right_nh.resolveName("image_rect"), 1, hintsRight);
00101                 cameraInfoLeft_.subscribe(left_nh, "camera_info", 1);
00102                 cameraInfoRight_.subscribe(right_nh, "camera_info", 1);
00103 
00104                 if(approxSync)
00105                 {
00106                         approxSync_ = new message_filters::Synchronizer<MyApproxSyncPolicy>(MyApproxSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
00107                         approxSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
00108                 }
00109                 else
00110                 {
00111                         exactSync_ = new message_filters::Synchronizer<MyExactSyncPolicy>(MyExactSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
00112                         exactSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
00113                 }
00114 
00115 
00116                 NODELET_INFO("\n%s subscribed to (%s sync):\n   %s,\n   %s,\n   %s,\n   %s",
00117                                 ros::this_node::getName().c_str(),
00118                                 approxSync?"approx":"exact",
00119                                 imageRectLeft_.getTopic().c_str(),
00120                                 imageRectRight_.getTopic().c_str(),
00121                                 cameraInfoLeft_.getTopic().c_str(),
00122                                 cameraInfoRight_.getTopic().c_str());
00123         }
00124 
00125         void callback(
00126                         const sensor_msgs::ImageConstPtr& imageRectLeft,
00127                         const sensor_msgs::ImageConstPtr& imageRectRight,
00128                         const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
00129                         const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
00130         {
00131                 if(!this->isPaused())
00132                 {
00133                         if(!(imageRectLeft->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
00134                                  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
00135                                  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
00136                                  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0) ||
00137                                 !(imageRectRight->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
00138                                   imageRectRight->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
00139                                   imageRectRight->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
00140                                   imageRectRight->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0))
00141                         {
00142                                 NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 (mono8 recommended)");
00143                                 return;
00144                         }
00145 
00146                         ros::Time stamp = imageRectLeft->header.stamp>imageRectRight->header.stamp?imageRectLeft->header.stamp:imageRectRight->header.stamp;
00147 
00148                         Transform localTransform = getTransform(this->frameId(), imageRectLeft->header.frame_id, stamp);
00149                         if(localTransform.isNull())
00150                         {
00151                                 return;
00152                         }
00153 
00154                         ros::WallTime time = ros::WallTime::now();
00155 
00156                         int quality = -1;
00157                         if(imageRectLeft->data.size() && imageRectRight->data.size())
00158                         {
00159                                 rtabmap::StereoCameraModel stereoModel = rtabmap_ros::stereoCameraModelFromROS(*cameraInfoLeft, *cameraInfoRight, localTransform);
00160                                 if(stereoModel.baseline() <= 0)
00161                                 {
00162                                         NODELET_FATAL("The stereo baseline (%f) should be positive (baseline=-Tx/fx). We assume a horizontal left/right stereo "
00163                                                           "setup where the Tx (or P(0,3)) is negative in the right camera info msg.", stereoModel.baseline());
00164                                         return;
00165                                 }
00166 
00167                                 if(stereoModel.baseline() > 10.0)
00168                                 {
00169                                         static bool shown = false;
00170                                         if(!shown)
00171                                         {
00172                                                 NODELET_WARN("Detected baseline (%f m) is quite large! Is your "
00173                                                                  "right camera_info P(0,3) correctly set? Note that "
00174                                                                  "baseline=-P(0,3)/P(0,0). This warning is printed only once.",
00175                                                                  stereoModel.baseline());
00176                                                 shown = true;
00177                                         }
00178                                 }
00179 
00180                                 cv_bridge::CvImagePtr ptrImageLeft = cv_bridge::toCvCopy(imageRectLeft, "mono8");
00181                                 cv_bridge::CvImagePtr ptrImageRight = cv_bridge::toCvCopy(imageRectRight, "mono8");
00182 
00183                                 UTimer stepTimer;
00184                                 //
00185                                 UDEBUG("localTransform = %s", localTransform.prettyPrint().c_str());
00186                                 rtabmap::SensorData data(
00187                                                 ptrImageLeft->image,
00188                                                 ptrImageRight->image,
00189                                                 stereoModel,
00190                                                 0,
00191                                                 rtabmap_ros::timestampFromROS(stamp));
00192 
00193                                 this->processData(data, stamp);
00194                         }
00195                         else
00196                         {
00197                                 NODELET_WARN("Odom: input images empty?!?");
00198                         }
00199                 }
00200         }
00201 
00202 protected:
00203         virtual void flushCallbacks()
00204         {
00205                 //flush callbacks
00206                 if(approxSync_)
00207                 {
00208                         delete approxSync_;
00209                         approxSync_ = new message_filters::Synchronizer<MyApproxSyncPolicy>(MyApproxSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
00210                         approxSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
00211                 }
00212                 if(exactSync_)
00213                 {
00214                         delete exactSync_;
00215                         exactSync_ = new message_filters::Synchronizer<MyExactSyncPolicy>(MyExactSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
00216                         exactSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
00217                 }
00218         }
00219 
00220 private:
00221         image_transport::SubscriberFilter imageRectLeft_;
00222         image_transport::SubscriberFilter imageRectRight_;
00223         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoLeft_;
00224         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoRight_;
00225         typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> MyApproxSyncPolicy;
00226         message_filters::Synchronizer<MyApproxSyncPolicy> * approxSync_;
00227         typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> MyExactSyncPolicy;
00228         message_filters::Synchronizer<MyExactSyncPolicy> * exactSync_;
00229         int queueSize_;
00230 };
00231 
00232 PLUGINLIB_EXPORT_CLASS(rtabmap_ros::StereoOdometry, nodelet::Nodelet);
00233 
00234 }
00235 


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Sun Jul 24 2016 03:49:08