mrpt_local_obstacles_node.cpp
Go to the documentation of this file.
00001 /***********************************************************************************
00002  * Revised BSD License *
00003  * Copyright (c) 2014-2015, Jose-Luis Blanco <jlblanco@ual.es> *
00004  * All rights reserved. *
00005  *                                                                                 *
00006  * Redistribution and use in source and binary forms, with or without *
00007  * modification, are permitted provided that the following conditions are met: *
00008  *     * Redistributions of source code must retain the above copyright *
00009  *       notice, this list of conditions and the following disclaimer. *
00010  *     * Redistributions in binary form must reproduce the above copyright *
00011  *       notice, this list of conditions and the following disclaimer in the *
00012  *       documentation and/or other materials provided with the distribution. *
00013  *     * Neither the name of the Vienna University of Technology nor the *
00014  *       names of its contributors may be used to endorse or promote products *
00015  *       derived from this software without specific prior written permission. *
00016  *                                                                                 *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  *AND *
00019  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020  **
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  **
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
00027  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
00028  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029  **
00030  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
00031  ***********************************************************************************/
00032 
00033 #include <ros/ros.h>
00034 
00035 #include <sensor_msgs/LaserScan.h>
00036 #include <sensor_msgs/PointCloud.h>
00037 #include <nav_msgs/Odometry.h>
00038 
00039 #include <tf/transform_listener.h>
00040 
00041 #include <mrpt_bridge/pose.h>
00042 #include <mrpt_bridge/laser_scan.h>
00043 #include <mrpt_bridge/point_cloud.h>
00044 
00045 #include <map>
00046 
00047 #include <mrpt/version.h>
00048 #include <mrpt/obs/CSensoryFrame.h>
00049 #include <mrpt/maps/CSimplePointsMap.h>
00050 #include <mrpt/maps/COccupancyGridMap2D.h>
00051 #include <mrpt/obs/CObservation2DRangeScan.h>
00052 using namespace mrpt::maps;
00053 using namespace mrpt::obs;
00054 
00055 #include <mrpt/system/string_utils.h>
00056 #include <mrpt/utils/CTimeLogger.h>
00057 #include <mrpt/utils/CConfigFile.h>
00058 #include <mrpt/gui/CDisplayWindow3D.h>
00059 #include <mrpt/opengl/CGridPlaneXY.h>
00060 #include <mrpt/opengl/CPointCloud.h>
00061 #include <mrpt/opengl/stock_objects.h>
00062 
00063 // The ROS node
00064 class LocalObstaclesNode
00065 {
00066    private:
00067         struct TAuxInitializer
00068         {
00069                 TAuxInitializer(int argc, char** argv)
00070                 {
00071                         ros::init(argc, argv, "mrpt_local_obstacles_node");
00072                 }
00073         };
00074 
00075         mrpt::utils::CTimeLogger m_profiler;
00076 
00077         TAuxInitializer m_auxinit;  
00078         ros::NodeHandle m_nh;  
00079         ros::NodeHandle m_localn;  
00080         bool m_show_gui;
00081         std::string m_frameid_reference;  
00082         std::string m_frameid_robot;  
00083         std::string
00084                 m_topic_local_map_pointcloud;  
00085         std::string m_source_topics_2dscan;  
00086         double m_time_window;  
00087 
00088         double m_publish_period;  
00089 
00090 
00091         ros::Timer m_timer_publish;
00092 
00093         // Sensor data:
00094         struct TInfoPerTimeStep
00095         {
00096                 CObservation::Ptr observation;
00097                 mrpt::poses::CPose3D robot_pose;
00098         };
00099         typedef std::multimap<double, TInfoPerTimeStep> TListObservations;
00100         TListObservations m_hist_obs;  
00101 
00102         boost::mutex m_hist_obs_mtx;
00103 
00105         CSimplePointsMap m_localmap_pts;
00106         // COccupancyGridMap2D m_localmap_grid;
00107 
00108         mrpt::gui::CDisplayWindow3D::Ptr m_gui_win;
00109 
00112         ros::Publisher m_pub_local_map_pointcloud;
00113         std::vector<ros::Subscriber>
00114                 m_subs_2dlaser;  
00115         tf::TransformListener m_tf_listener;  
00116 
00124         template <typename CALLBACK_METHOD_TYPE>
00125         size_t subscribeToMultipleTopics(
00126                 const std::string& lstTopics, std::vector<ros::Subscriber>& subs,
00127                 CALLBACK_METHOD_TYPE cb)
00128         {
00129                 std::vector<std::string> lstSources;
00130                 mrpt::system::tokenize(lstTopics, " ,\t\n", lstSources);
00131                 subs.resize(lstSources.size());
00132                 for (size_t i = 0; i < lstSources.size(); i++)
00133                         subs[i] = m_nh.subscribe(lstSources[i], 1, cb, this);
00134                 return lstSources.size();
00135         }
00136 
00139         void onNewSensor_Laser2D(const sensor_msgs::LaserScanConstPtr& scan)
00140         {
00141                 mrpt::utils::CTimeLoggerEntry tle(m_profiler, "onNewSensor_Laser2D");
00142 
00143                 // Get the relative position of the sensor wrt the robot:
00144                 tf::StampedTransform sensorOnRobot;
00145                 try
00146                 {
00147                         mrpt::utils::CTimeLoggerEntry tle2(
00148                                 m_profiler, "onNewSensor_Laser2D.lookupTransform_sensor");
00149                         m_tf_listener.lookupTransform(
00150                                 m_frameid_robot, scan->header.frame_id, ros::Time(0),
00151                                 sensorOnRobot);
00152                 }
00153                 catch (tf::TransformException& ex)
00154                 {
00155                         ROS_ERROR("%s", ex.what());
00156                         return;
00157                 }
00158 
00159                 // Convert data to MRPT format:
00160                 mrpt::poses::CPose3D sensorOnRobot_mrpt;
00161                 mrpt_bridge::convert(sensorOnRobot, sensorOnRobot_mrpt);
00162                 // In MRPT, CObservation2DRangeScan holds both: sensor data + relative
00163                 // pose:
00164                 CObservation2DRangeScan::Ptr obsScan =
00165                         mrpt::make_aligned_shared<CObservation2DRangeScan>();
00166                 mrpt_bridge::convert(*scan, sensorOnRobot_mrpt, *obsScan);
00167 
00168                 ROS_DEBUG(
00169                         "[onNewSensor_Laser2D] %u rays, sensor pose on robot %s",
00170                         static_cast<unsigned int>(obsScan->scan.size()),
00171                         sensorOnRobot_mrpt.asString().c_str());
00172 
00173                 // Get sensor timestamp:
00174                 const double timestamp = scan->header.stamp.toSec();
00175 
00176                 // Get robot pose at that time in the reference frame, typ: /odom ->
00177                 // /base_link
00178                 mrpt::poses::CPose3D robotPose;
00179                 try
00180                 {
00181                         mrpt::utils::CTimeLoggerEntry tle3(
00182                                 m_profiler, "onNewSensor_Laser2D.lookupTransform_robot");
00183                         tf::StampedTransform tx;
00184 
00185                         try
00186                         {
00187                                 m_tf_listener.lookupTransform(
00188                                         m_frameid_reference, m_frameid_robot, scan->header.stamp,
00189                                         tx);
00190                         }
00191                         catch (tf::ExtrapolationException&)
00192                         {
00193                                 // if we need a "too much " recent robot pose,be happy with the
00194                                 // latest one:
00195                                 m_tf_listener.lookupTransform(
00196                                         m_frameid_reference, m_frameid_robot, ros::Time(0), tx);
00197                         }
00198                         mrpt_bridge::convert(tx, robotPose);
00199                         ROS_DEBUG(
00200                                 "[onNewSensor_Laser2D] robot pose %s",
00201                                 robotPose.asString().c_str());
00202                 }
00203                 catch (tf::TransformException& ex)
00204                 {
00205                         ROS_ERROR("%s", ex.what());
00206                         return;
00207                 }
00208 
00209                 // Insert into the observation history:
00210                 TInfoPerTimeStep ipt;
00211                 ipt.observation = obsScan;
00212                 ipt.robot_pose = robotPose;
00213 
00214                 m_hist_obs_mtx.lock();
00215                 m_hist_obs.insert(
00216                         m_hist_obs.end(), TListObservations::value_type(timestamp, ipt));
00217                 m_hist_obs_mtx.unlock();
00218 
00219         }  // end onNewSensor_Laser2D
00220 
00222         void onDoPublish(const ros::TimerEvent&)
00223         {
00224                 mrpt::utils::CTimeLoggerEntry tle(m_profiler, "onDoPublish");
00225 
00226                 // Purge old observations & latch a local copy:
00227                 TListObservations obs;
00228                 {
00229                         mrpt::utils::CTimeLoggerEntry tle(
00230                                 m_profiler, "onDoPublish.removingOld");
00231                         m_hist_obs_mtx.lock();
00232 
00233                         // Purge old obs:
00234                         if (!m_hist_obs.empty())
00235                         {
00236                                 const double last_time = m_hist_obs.rbegin()->first;
00237                                 TListObservations::iterator it_first_valid =
00238                                         m_hist_obs.lower_bound(last_time - m_time_window);
00239                                 const size_t nToRemove =
00240                                         std::distance(m_hist_obs.begin(), it_first_valid);
00241                                 ROS_DEBUG(
00242                                         "[onDoPublish] Removing %u old entries, last_time=%lf",
00243                                         static_cast<unsigned int>(nToRemove), last_time);
00244                                 m_hist_obs.erase(m_hist_obs.begin(), it_first_valid);
00245                         }
00246                         // Local copy in this thread:
00247                         obs = m_hist_obs;
00248                         m_hist_obs_mtx.unlock();
00249                 }
00250 
00251                 ROS_DEBUG(
00252                         "Building local map with %u observations.",
00253                         static_cast<unsigned int>(obs.size()));
00254                 if (obs.empty()) return;
00255 
00256                 // Build local map(s):
00257                 // -----------------------------------------------
00258                 m_localmap_pts.clear();
00259                 mrpt::poses::CPose3D curRobotPose;
00260                 {
00261                         mrpt::utils::CTimeLoggerEntry tle2(
00262                                 m_profiler, "onDoPublish.buildLocalMap");
00263 
00264                         // Get the latest robot pose in the reference frame (typ: /odom ->
00265                         // /base_link)
00266                         // so we can build the local map RELATIVE to it:
00267                         try
00268                         {
00269                                 tf::StampedTransform tx;
00270                                 m_tf_listener.lookupTransform(
00271                                         m_frameid_reference, m_frameid_robot, ros::Time(0), tx);
00272                                 mrpt_bridge::convert(tx, curRobotPose);
00273                                 ROS_DEBUG(
00274                                         "[onDoPublish] Building local map relative to latest robot "
00275                                         "pose: %s",
00276                                         curRobotPose.asString().c_str());
00277                         }
00278                         catch (tf::TransformException& ex)
00279                         {
00280                                 ROS_ERROR("%s", ex.what());
00281                                 return;
00282                         }
00283 
00284                         // For each observation: compute relative robot pose & insert obs
00285                         // into map:
00286                         for (TListObservations::const_iterator it = obs.begin();
00287                                  it != obs.end(); ++it)
00288                         {
00289                                 const TInfoPerTimeStep& ipt = it->second;
00290 
00291                                 // Relative pose in the past:
00292                                 mrpt::poses::CPose3D relPose(mrpt::poses::UNINITIALIZED_POSE);
00293                                 relPose.inverseComposeFrom(ipt.robot_pose, curRobotPose);
00294 
00295                                 // Insert obs:
00296                                 m_localmap_pts.insertObservationPtr(ipt.observation, &relPose);
00297 
00298                         }  // end for
00299                 }
00300 
00301                 // Publish them:
00302                 if (m_pub_local_map_pointcloud.getNumSubscribers() > 0)
00303                 {
00304                         sensor_msgs::PointCloudPtr msg_pts =
00305                                 sensor_msgs::PointCloudPtr(new sensor_msgs::PointCloud);
00306                         msg_pts->header.frame_id = m_frameid_robot;
00307                         msg_pts->header.stamp = ros::Time(obs.rbegin()->first);
00308                         mrpt_bridge::point_cloud::mrpt2ros(
00309                                 m_localmap_pts, msg_pts->header, *msg_pts);
00310                         m_pub_local_map_pointcloud.publish(msg_pts);
00311                 }
00312 
00313                 // Show gui:
00314                 if (m_show_gui)
00315                 {
00316                         if (!m_gui_win)
00317                         {
00318                                 m_gui_win = mrpt::gui::CDisplayWindow3D::Create(
00319                                         "LocalObstaclesNode", 800, 600);
00320                                 mrpt::opengl::COpenGLScene::Ptr& scene =
00321                                         m_gui_win->get3DSceneAndLock();
00322                                 scene->insert(
00323                                         mrpt::make_aligned_shared<mrpt::opengl::CGridPlaneXY>());
00324                                 scene->insert(
00325                                         mrpt::opengl::stock_objects::CornerXYZSimple(1.0, 4.0));
00326 
00327                                 mrpt::opengl::CSetOfObjects::Ptr gl_obs =
00328                                         mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
00329                                 gl_obs->setName("obstacles");
00330                                 scene->insert(gl_obs);
00331 
00332                                 mrpt::opengl::CPointCloud::Ptr gl_pts =
00333                                         mrpt::make_aligned_shared<mrpt::opengl::CPointCloud>();
00334                                 gl_pts->setName("points");
00335                                 gl_pts->setPointSize(2.0);
00336                                 gl_pts->setColor_u8(mrpt::utils::TColor(0x0000ff));
00337                                 scene->insert(gl_pts);
00338 
00339                                 m_gui_win->unlockAccess3DScene();
00340                         }
00341 
00342                         mrpt::opengl::COpenGLScene::Ptr& scene =
00343                                 m_gui_win->get3DSceneAndLock();
00344                         mrpt::opengl::CSetOfObjects::Ptr gl_obs =
00345                                 std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
00346                                         scene->getByName("obstacles"));
00347                         ROS_ASSERT(!!gl_obs);
00348                         gl_obs->clear();
00349 
00350                         mrpt::opengl::CPointCloud::Ptr gl_pts =
00351                                 std::dynamic_pointer_cast<mrpt::opengl::CPointCloud>(
00352                                         scene->getByName("points"));
00353 
00354                         for (TListObservations::const_iterator it = obs.begin();
00355                                  it != obs.end(); ++it)
00356                         {
00357                                 const TInfoPerTimeStep& ipt = it->second;
00358                                 // Relative pose in the past:
00359                                 mrpt::poses::CPose3D relPose(mrpt::poses::UNINITIALIZED_POSE);
00360                                 relPose.inverseComposeFrom(ipt.robot_pose, curRobotPose);
00361 
00362                                 mrpt::opengl::CSetOfObjects::Ptr gl_axis =
00363                                         mrpt::opengl::stock_objects::CornerXYZSimple(0.9, 2.0);
00364                                 gl_axis->setPose(relPose);
00365                                 gl_obs->insert(gl_axis);
00366                         }  // end for
00367 
00368                         gl_pts->loadFromPointsMap(&m_localmap_pts);
00369 
00370                         m_gui_win->unlockAccess3DScene();
00371                         m_gui_win->repaint();
00372                 }
00373 
00374         }  // onDoPublish
00375 
00376    public:
00378         LocalObstaclesNode(int argc, char** argv)
00379                 : m_auxinit(argc, argv),
00380                   m_nh(),
00381                   m_localn("~"),
00382                   m_show_gui(true),
00383                   m_frameid_reference("odom"),
00384                   m_frameid_robot("base_link"),
00385                   m_topic_local_map_pointcloud("local_map_pointcloud"),
00386                   m_source_topics_2dscan("scan,laser1"),
00387                   m_time_window(0.2),
00388                   m_publish_period(0.05)
00389         {
00390                 // Load params:
00391                 m_localn.param("show_gui", m_show_gui, m_show_gui);
00392                 m_localn.param(
00393                         "frameid_reference", m_frameid_reference, m_frameid_reference);
00394                 m_localn.param("frameid_robot", m_frameid_robot, m_frameid_robot);
00395                 m_localn.param(
00396                         "topic_local_map_pointcloud", m_topic_local_map_pointcloud,
00397                         m_topic_local_map_pointcloud);
00398                 m_localn.param(
00399                         "source_topics_2dscan", m_source_topics_2dscan,
00400                         m_source_topics_2dscan);
00401                 m_localn.param("time_window", m_time_window, m_time_window);
00402                 m_localn.param("publish_period", m_publish_period, m_publish_period);
00403 
00404                 ROS_ASSERT(m_time_window > m_publish_period);
00405                 ROS_ASSERT(m_publish_period > 0);
00406 
00407                 // Init ROS publishers:
00408                 m_pub_local_map_pointcloud = m_nh.advertise<sensor_msgs::PointCloud>(
00409                         m_topic_local_map_pointcloud, 10);
00410 
00411                 // Init ROS subs:
00412                 // Subscribe to one or more laser sources:
00413                 size_t nSubsTotal = 0;
00414                 nSubsTotal += this->subscribeToMultipleTopics(
00415                         m_source_topics_2dscan, m_subs_2dlaser,
00416                         &LocalObstaclesNode::onNewSensor_Laser2D);
00417 
00418                 ROS_INFO(
00419                         "Total number of sensor subscriptions: %u\n",
00420                         static_cast<unsigned int>(nSubsTotal));
00421                 ROS_ASSERT_MSG(
00422                         nSubsTotal > 0,
00423                         "*Error* It is mandatory to set at least one source topic for "
00424                         "sensory information!");
00425 
00426                 // Local map params:
00427                 m_localmap_pts.insertionOptions.minDistBetweenLaserPoints = 0;
00428                 m_localmap_pts.insertionOptions.also_interpolate = false;
00429 
00430                 // Init timers:
00431                 m_timer_publish = m_nh.createTimer(
00432                         ros::Duration(m_publish_period), &LocalObstaclesNode::onDoPublish,
00433                         this);
00434 
00435         }  // end ctor
00436 
00437 };  // end class
00438 
00439 int main(int argc, char** argv)
00440 {
00441         LocalObstaclesNode the_node(argc, argv);
00442         ros::spin();
00443         return 0;
00444 }


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Sep 18 2017 03:12:09