CoreWrapper.h
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 #ifndef COREWRAPPER_H_
00029 #define COREWRAPPER_H_
00030 
00031 
00032 #include <ros/ros.h>
00033 
00034 #include <tf/tf.h>
00035 #include <tf/transform_broadcaster.h>
00036 #include <tf/transform_listener.h>
00037 
00038 #include <std_srvs/Empty.h>
00039 
00040 #include <cv_bridge/cv_bridge.h>
00041 
00042 #include <std_msgs/Empty.h>
00043 #include <std_msgs/Int32.h>
00044 #include <sensor_msgs/PointCloud2.h>
00045 #include <sensor_msgs/Image.h>
00046 #include <sensor_msgs/CameraInfo.h>
00047 #include <sensor_msgs/LaserScan.h>
00048 #include <nav_msgs/Odometry.h>
00049 #include <nav_msgs/GetMap.h>
00050 
00051 #include <rtabmap/core/Statistics.h>
00052 #include <rtabmap/core/Parameters.h>
00053 #include <rtabmap/core/Rtabmap.h>
00054 
00055 #include "rtabmap_ros/GetMap.h"
00056 #include "rtabmap_ros/ListLabels.h"
00057 #include "rtabmap_ros/PublishMap.h"
00058 #include "rtabmap_ros/SetGoal.h"
00059 #include "rtabmap_ros/SetLabel.h"
00060 
00061 #include <message_filters/subscriber.h>
00062 #include <message_filters/synchronizer.h>
00063 #include <message_filters/sync_policies/approximate_time.h>
00064 #include <message_filters/sync_policies/exact_time.h>
00065 
00066 #include <image_transport/image_transport.h>
00067 #include <image_transport/subscriber_filter.h>
00068 
00069 #include <pcl/point_types.h>
00070 #include <pcl/point_cloud.h>
00071 
00072 #ifdef WITH_OCTOMAP
00073 #include <octomap_msgs/GetOctomap.h>
00074 #endif
00075 
00076 #include <actionlib/client/simple_action_client.h>
00077 #include <move_base_msgs/MoveBaseAction.h>
00078 #include <move_base_msgs/MoveBaseActionGoal.h>
00079 #include <move_base_msgs/MoveBaseActionResult.h>
00080 #include <move_base_msgs/MoveBaseActionFeedback.h>
00081 #include <actionlib_msgs/GoalStatusArray.h>
00082 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00083 
00084 namespace octomap{
00085 class OcTree;
00086 }
00087 
00088 class CoreWrapper
00089 {
00090 public:
00091         CoreWrapper(bool deleteDbOnStart);
00092         virtual ~CoreWrapper();
00093 
00094 private:
00095         void setupCallbacks(bool subscribeDepth, bool subscribeLaserScan, bool subscribeStereo, int queueSize, bool stereoApproxSync);
00096         void defaultCallback(const sensor_msgs::ImageConstPtr & imageMsg); // no odom
00097 
00098         bool commonOdomUpdate(const nav_msgs::OdometryConstPtr & odomMsg);
00099         bool commonOdomTFUpdate(const ros::Time & stamp); // TF odom
00100         rtabmap::Transform getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const;
00101 
00102         void commonDepthCallback(
00103                                 const std::string & odomFrameId,
00104                                 const sensor_msgs::ImageConstPtr& imageMsg,
00105                                 const sensor_msgs::ImageConstPtr& imageDepthMsg,
00106                                 const sensor_msgs::CameraInfoConstPtr& camInfoMsg,
00107                                 const sensor_msgs::LaserScanConstPtr& scanMsg);
00108         void commonStereoCallback(
00109                                 const std::string & odomFrameId,
00110                                 const sensor_msgs::ImageConstPtr& leftImageMsg,
00111                                 const sensor_msgs::ImageConstPtr& rightImageMsg,
00112                                 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00113                                 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
00114                                 const sensor_msgs::LaserScanConstPtr& scanMsg);
00115 
00116         // with odom msg
00117         void depthCallback(
00118                         const sensor_msgs::ImageConstPtr& imageMsg,
00119                         const nav_msgs::OdometryConstPtr & odomMsg,
00120                         const sensor_msgs::ImageConstPtr& imageDepthMsg,
00121                         const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00122         void depthScanCallback(
00123                         const sensor_msgs::ImageConstPtr& imageMsg,
00124                         const nav_msgs::OdometryConstPtr & odomMsg,
00125                         const sensor_msgs::ImageConstPtr& imageDepthMsg,
00126                         const sensor_msgs::CameraInfoConstPtr& camInfoMsg,
00127                         const sensor_msgs::LaserScanConstPtr& scanMsg);
00128         void stereoCallback(
00129                         const sensor_msgs::ImageConstPtr& leftImageMsg,
00130                         const sensor_msgs::ImageConstPtr& rightImageMsg,
00131                         const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00132                         const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
00133                         const nav_msgs::OdometryConstPtr & odomMsg);
00134         void stereoScanCallback(
00135                         const sensor_msgs::ImageConstPtr& leftImageMsg,
00136                         const sensor_msgs::ImageConstPtr& rightImageMsg,
00137                         const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00138                         const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
00139                         const sensor_msgs::LaserScanConstPtr& scanMsg,
00140                         const nav_msgs::OdometryConstPtr & odomMsg);
00141 
00142         // without odom, when TF is used for odom
00143         void depthTFCallback(
00144                         const sensor_msgs::ImageConstPtr& imageMsg,
00145                         const sensor_msgs::ImageConstPtr& imageDepthMsg,
00146                         const sensor_msgs::CameraInfoConstPtr& camInfoMsg);
00147         void depthScanTFCallback(
00148                         const sensor_msgs::ImageConstPtr& imageMsg,
00149                         const sensor_msgs::ImageConstPtr& imageDepthMsg,
00150                         const sensor_msgs::CameraInfoConstPtr& camInfoMsg,
00151                         const sensor_msgs::LaserScanConstPtr& scanMsg);
00152         void stereoTFCallback(
00153                         const sensor_msgs::ImageConstPtr& leftImageMsg,
00154                         const sensor_msgs::ImageConstPtr& rightImageMsg,
00155                         const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00156                         const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg);
00157         void stereoScanTFCallback(
00158                         const sensor_msgs::ImageConstPtr& leftImageMsg,
00159                         const sensor_msgs::ImageConstPtr& rightImageMsg,
00160                         const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
00161                         const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
00162                         const sensor_msgs::LaserScanConstPtr& scanMsg);
00163 
00164         void goalCommonCallback(const std::vector<std::pair<int, rtabmap::Transform> > & poses);
00165         void goalCallback(const geometry_msgs::PoseStampedConstPtr & msg);
00166         void goalGlobalCallback(const geometry_msgs::PoseStampedConstPtr & msg);
00167         void updateGoal(const ros::Time & stamp);
00168 
00169         void process(
00170                         int id,
00171                         const ros::Time & stamp,
00172                         const cv::Mat & image,
00173                         const rtabmap::Transform & odom = rtabmap::Transform(),
00174                         const std::string & odomFrameId = "",
00175                         float odomRotationalVariance = 1.0f,
00176                         float odomTransitionalVariance = 1.0f,
00177                         const cv::Mat & depthOrRightImage = cv::Mat(),
00178                         float fx = 0.0f,
00179                         float fyOrBaseline = 0.0f,
00180                         float cx = 0.0f,
00181                         float cy = 0.0f,
00182                         const rtabmap::Transform & localTransform = rtabmap::Transform(),
00183                         const cv::Mat & scan = cv::Mat(),
00184                         int scanMaxPts = 0);
00185 
00186         bool updateRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00187         bool resetRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00188         bool pauseRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00189         bool resumeRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00190         bool triggerNewMapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00191         bool backupDatabaseCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00192         bool setModeLocalizationCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00193         bool setModeMappingCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00194         bool getMapCallback(rtabmap_ros::GetMap::Request& req, rtabmap_ros::GetMap::Response& res);
00195         bool getProjMapCallback(nav_msgs::GetMap::Request  &req, nav_msgs::GetMap::Response &res);
00196         bool getGridMapCallback(nav_msgs::GetMap::Request  &req, nav_msgs::GetMap::Response &res);
00197         bool publishMapCallback(rtabmap_ros::PublishMap::Request&, rtabmap_ros::PublishMap::Response&);
00198         bool setGoalCallback(rtabmap_ros::SetGoal::Request& req, rtabmap_ros::SetGoal::Response& res);
00199         bool setLabelCallback(rtabmap_ros::SetLabel::Request& req, rtabmap_ros::SetLabel::Response& res);
00200         bool listLabelsCallback(rtabmap_ros::ListLabels::Request& req, rtabmap_ros::ListLabels::Response& res);
00201 #ifdef WITH_OCTOMAP
00202         bool octomapBinaryCallback(octomap_msgs::GetOctomap::Request  &req, octomap_msgs::GetOctomap::Response &res);
00203         bool octomapFullCallback(octomap_msgs::GetOctomap::Request  &req, octomap_msgs::GetOctomap::Response &res);
00204 #endif
00205 
00206         rtabmap::ParametersMap loadParameters(const std::string & configFile);
00207         void saveParameters(const std::string & configFile);
00208 
00209         void publishLoop(double tfDelay);
00210 
00211         std::map<int, rtabmap::Transform> updateMapCaches(const std::map<int, rtabmap::Transform> & poses,
00212                         bool updateCloud,
00213                         bool updateProj,
00214                         bool updateGrid,
00215                         const std::map<int, rtabmap::Signature> & signatures = std::map<int, rtabmap::Signature>());
00216 
00217         void publishStats(const ros::Time & stamp);
00218         void publishMaps(const std::map<int, rtabmap::Transform> & poses, const ros::Time & stamp);
00219         void publishCurrentGoal(const ros::Time & stamp);
00220         void goalDoneCb(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr& result);
00221         void goalActiveCb();
00222         void goalFeedbackCb(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
00223         void publishLocalPath(const ros::Time & stamp);
00224 
00225 #ifdef WITH_OCTOMAP
00226         octomap::OcTree * createOctomap();
00227 #endif
00228 
00229 private:
00230         rtabmap::Rtabmap rtabmap_;
00231         bool paused_;
00232         rtabmap::Transform lastPose_;
00233         ros::Time lastPoseStamp_;
00234         float rotVariance_;
00235         float transVariance_;
00236         rtabmap::Transform currentMetricGoal_;
00237         bool latestNodeWasReached_;
00238         rtabmap::ParametersMap parameters_;
00239 
00240         std::string frameId_;
00241         std::string mapFrameId_;
00242         std::string odomFrameId_;
00243         std::string configPath_;
00244         std::string databasePath_;
00245         bool waitForTransform_;
00246         bool useActionForGoal_;
00247 
00248         // mapping stuff
00249         int cloudDecimation_;
00250         double cloudMaxDepth_;
00251         double cloudVoxelSize_;
00252         bool cloudOutputVoxelized_;
00253         double projMaxGroundAngle_;
00254         int projMinClusterSize_;
00255         double projMaxHeight_;
00256         double gridCellSize_;
00257         double gridSize_;
00258         bool gridEroded_;
00259         double mapFilterRadius_;
00260         double mapFilterAngle_;
00261         bool mapCacheCleanup_;
00262 
00263         tf::Transform mapToOdom_;
00264         boost::mutex mapToOdomMutex_;
00265 
00266         std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > clouds_;
00267         std::map<int, std::pair<cv::Mat, cv::Mat> > projMaps_; // <ground, obstacles>
00268         std::map<int, std::pair<cv::Mat, cv::Mat> > gridMaps_; // <ground, obstacles>
00269 
00270         ros::Publisher infoPub_;
00271         ros::Publisher mapDataPub_;
00272         ros::Publisher mapGraphPub_;
00273         ros::Publisher labelsPub_;
00274         ros::Publisher cloudMapPub_;
00275         ros::Publisher projMapPub_;
00276         ros::Publisher gridMapPub_;
00277 
00278         //Planning stuff
00279         ros::Subscriber goalSub_;
00280         ros::Subscriber goalGlobalSub_;
00281         ros::Publisher nextMetricGoalPub_;
00282         ros::Publisher goalReachedPub_;
00283         ros::Publisher globalPathPub_;
00284         ros::Publisher localPathPub_;
00285 
00286         // for loop closure detection only
00287         image_transport::Subscriber defaultSub_;
00288 
00289         //for depth callback
00290         image_transport::SubscriberFilter imageSub_;
00291         image_transport::SubscriberFilter imageDepthSub_;
00292         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoSub_;
00293 
00294         //stereo callback
00295         image_transport::SubscriberFilter imageRectLeft_;
00296         image_transport::SubscriberFilter imageRectRight_;
00297         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoLeft_;
00298         message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoRight_;
00299 
00300         message_filters::Subscriber<nav_msgs::Odometry> odomSub_;
00301         message_filters::Subscriber<sensor_msgs::LaserScan> scanSub_;
00302 
00303         typedef message_filters::sync_policies::ApproximateTime<
00304                         sensor_msgs::Image,
00305                         nav_msgs::Odometry,
00306                         sensor_msgs::Image,
00307                         sensor_msgs::CameraInfo,
00308                         sensor_msgs::LaserScan> MyDepthScanSyncPolicy;
00309         message_filters::Synchronizer<MyDepthScanSyncPolicy> * depthScanSync_;
00310 
00311         typedef message_filters::sync_policies::ApproximateTime<
00312                         sensor_msgs::Image,
00313                         nav_msgs::Odometry,
00314                         sensor_msgs::Image,
00315                         sensor_msgs::CameraInfo> MyDepthSyncPolicy;
00316         message_filters::Synchronizer<MyDepthSyncPolicy> * depthSync_;
00317 
00318         typedef message_filters::sync_policies::ApproximateTime<
00319                         sensor_msgs::Image,
00320                         sensor_msgs::Image,
00321                         sensor_msgs::CameraInfo,
00322                         sensor_msgs::CameraInfo,
00323                         sensor_msgs::LaserScan,
00324                         nav_msgs::Odometry> MyStereoScanSyncPolicy;
00325         message_filters::Synchronizer<MyStereoScanSyncPolicy> * stereoScanSync_;
00326 
00327         typedef message_filters::sync_policies::ApproximateTime<
00328                         sensor_msgs::Image,
00329                         sensor_msgs::Image,
00330                         sensor_msgs::CameraInfo,
00331                         sensor_msgs::CameraInfo,
00332                         nav_msgs::Odometry> MyStereoApproxSyncPolicy;
00333         message_filters::Synchronizer<MyStereoApproxSyncPolicy> * stereoApproxSync_;
00334 
00335         typedef message_filters::sync_policies::ExactTime<
00336                         sensor_msgs::Image,
00337                         sensor_msgs::Image,
00338                         sensor_msgs::CameraInfo,
00339                         sensor_msgs::CameraInfo,
00340                         nav_msgs::Odometry> MyStereoExactSyncPolicy;
00341         message_filters::Synchronizer<MyStereoExactSyncPolicy> * stereoExactSync_;
00342 
00343         // without odom, when TF is used for odom
00344         typedef message_filters::sync_policies::ApproximateTime<
00345                         sensor_msgs::Image,
00346                         sensor_msgs::Image,
00347                         sensor_msgs::CameraInfo,
00348                         sensor_msgs::LaserScan> MyDepthScanTFSyncPolicy;
00349         message_filters::Synchronizer<MyDepthScanTFSyncPolicy> * depthScanTFSync_;
00350 
00351         typedef message_filters::sync_policies::ApproximateTime<
00352                         sensor_msgs::Image,
00353                         sensor_msgs::Image,
00354                         sensor_msgs::CameraInfo> MyDepthTFSyncPolicy;
00355         message_filters::Synchronizer<MyDepthTFSyncPolicy> * depthTFSync_;
00356 
00357         typedef message_filters::sync_policies::ApproximateTime<
00358                         sensor_msgs::Image,
00359                         sensor_msgs::Image,
00360                         sensor_msgs::CameraInfo,
00361                         sensor_msgs::CameraInfo,
00362                         sensor_msgs::LaserScan> MyStereoScanTFSyncPolicy;
00363         message_filters::Synchronizer<MyStereoScanTFSyncPolicy> * stereoScanTFSync_;
00364 
00365         typedef message_filters::sync_policies::ApproximateTime<
00366                         sensor_msgs::Image,
00367                         sensor_msgs::Image,
00368                         sensor_msgs::CameraInfo,
00369                         sensor_msgs::CameraInfo> MyStereoApproxTFSyncPolicy;
00370         message_filters::Synchronizer<MyStereoApproxTFSyncPolicy> * stereoApproxTFSync_;
00371 
00372         typedef message_filters::sync_policies::ExactTime<
00373                         sensor_msgs::Image,
00374                         sensor_msgs::Image,
00375                         sensor_msgs::CameraInfo,
00376                         sensor_msgs::CameraInfo> MyStereoExactTFSyncPolicy;
00377         message_filters::Synchronizer<MyStereoExactTFSyncPolicy> * stereoExactTFSync_;
00378 
00379         tf::TransformBroadcaster tfBroadcaster_;
00380         tf::TransformListener tfListener_;
00381 
00382         ros::ServiceServer updateSrv_;
00383         ros::ServiceServer resetSrv_;
00384         ros::ServiceServer pauseSrv_;
00385         ros::ServiceServer resumeSrv_;
00386         ros::ServiceServer triggerNewMapSrv_;
00387         ros::ServiceServer backupDatabase_;
00388         ros::ServiceServer setModeLocalizationSrv_;
00389         ros::ServiceServer setModeMappingSrv_;
00390         ros::ServiceServer getMapDataSrv_;
00391         ros::ServiceServer getProjMapSrv_;
00392         ros::ServiceServer getGridMapSrv_;
00393         ros::ServiceServer publishMapDataSrv_;
00394         ros::ServiceServer setGoalSrv_;
00395         ros::ServiceServer setLabelSrv_;
00396         ros::ServiceServer listLabelsSrv_;
00397 #ifdef WITH_OCTOMAP
00398         ros::ServiceServer octomapBinarySrv_;
00399         ros::ServiceServer octomapFullSrv_;
00400 #endif
00401 
00402         MoveBaseClient mbClient_;
00403 
00404         boost::thread* transformThread_;
00405 
00406         float rate_;
00407         ros::Time time_;
00408 };
00409 
00410 #endif /* COREWRAPPER_H_ */


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