34 #include <mrpt/config/CConfigFile.h> 35 #include <mrpt/gui/CDisplayWindow3D.h> 36 #include <mrpt/maps/COccupancyGridMap2D.h> 37 #include <mrpt/maps/CSimplePointsMap.h> 38 #include <mrpt/obs/CObservation2DRangeScan.h> 39 #include <mrpt/obs/CObservationPointCloud.h> 40 #include <mrpt/obs/CSensoryFrame.h> 41 #include <mrpt/opengl/CGridPlaneXY.h> 42 #include <mrpt/opengl/COpenGLScene.h> 43 #include <mrpt/opengl/CPointCloud.h> 44 #include <mrpt/opengl/stock_objects.h> 45 #include <mrpt/ros1bridge/laser_scan.h> 46 #include <mrpt/ros1bridge/point_cloud2.h> 47 #include <mrpt/ros1bridge/pose.h> 48 #include <mrpt/system/CTimeLogger.h> 49 #include <mrpt/system/string_utils.h> 50 #include <nav_msgs/Odometry.h> 52 #include <sensor_msgs/LaserScan.h> 53 #include <sensor_msgs/PointCloud2.h> 73 ros::init(argc, argv,
"mrpt_local_obstacles_node");
83 bool m_show_gui =
true;
88 std::string m_topic_local_map_pointcloud =
"local_map_pointcloud";
93 double m_time_window = 0.20;
94 double m_publish_period = 0.05;
106 boost::mutex m_hist_obs_mtx;
110 CSimplePointsMap::Ptr m_localmap_pts = CSimplePointsMap::Create();
142 template <
typename CALLBACK_METHOD_TYPE>
144 const std::string& lstTopics, std::vector<ros::Subscriber>& subs,
145 CALLBACK_METHOD_TYPE cb)
147 std::vector<std::string> lstSources;
148 mrpt::system::tokenize(lstTopics,
" ,\t\n", lstSources);
149 subs.resize(lstSources.size());
150 for (
size_t i = 0; i < lstSources.size(); i++)
151 subs[i] = m_nh.
subscribe(lstSources[i], 1, cb,
this);
152 return lstSources.size();
159 CTimeLoggerEntry tle(m_profiler,
"onNewSensor_Laser2D");
164 geometry_msgs::TransformStamped sensorOnRobot;
167 CTimeLoggerEntry tle2(
168 m_profiler,
"onNewSensor_Laser2D.lookupTransform_sensor");
171 m_frameid_robot, scan->header.frame_id, scan->header.stamp,
181 const mrpt::poses::CPose3D sensorOnRobot_mrpt = [&]() {
184 return mrpt::ros1bridge::fromROS(tx);
189 auto obsScan = CObservation2DRangeScan::Create();
190 mrpt::ros1bridge::fromROS(*scan, sensorOnRobot_mrpt, *obsScan);
193 "[onNewSensor_Laser2D] %u rays, sensor pose on robot %s",
194 static_cast<unsigned int>(obsScan->getScanSize()),
195 sensorOnRobot_mrpt.asString().c_str());
198 const double timestamp = scan->header.stamp.toSec();
202 mrpt::poses::CPose3D robotPose;
205 CTimeLoggerEntry tle3(
206 m_profiler,
"onNewSensor_Laser2D.lookupTransform_robot");
208 geometry_msgs::TransformStamped robotTfStamp;
212 m_frameid_reference, m_frameid_robot, scan->header.stamp,
224 return mrpt::ros1bridge::fromROS(tx);
228 "[onNewSensor_Laser2D] robot pose %s",
229 robotPose.asString().c_str());
242 m_hist_obs_mtx.lock();
244 m_hist_obs.end(), TListObservations::value_type(timestamp, ipt));
245 m_hist_obs_mtx.unlock();
253 CTimeLoggerEntry tle(m_profiler,
"onNewSensor_PointCloud");
257 geometry_msgs::TransformStamped sensorOnRobot;
260 CTimeLoggerEntry tle2(
261 m_profiler,
"onNewSensor_PointCloud.lookupTransform_sensor");
264 m_frameid_robot, pts->header.frame_id, pts->header.stamp,
274 const mrpt::poses::CPose3D sensorOnRobot_mrpt = [&]() {
277 return mrpt::ros1bridge::fromROS(tx);
282 auto obsPts = CObservationPointCloud::Create();
283 const auto ptsMap = mrpt::maps::CSimplePointsMap::Create();
284 obsPts->pointcloud = ptsMap;
285 obsPts->sensorPose = sensorOnRobot_mrpt;
286 mrpt::ros1bridge::fromROS(*pts, *ptsMap);
289 "[onNewSensor_PointCloud] %u points, sensor pose on robot %s",
290 static_cast<unsigned int>(ptsMap->size()),
291 sensorOnRobot_mrpt.asString().c_str());
294 const double timestamp = pts->header.stamp.toSec();
298 mrpt::poses::CPose3D robotPose;
301 CTimeLoggerEntry tle3(
302 m_profiler,
"onNewSensor_PointCloud.lookupTransform_robot");
304 geometry_msgs::TransformStamped robotTfStamp;
308 m_frameid_reference, m_frameid_robot, pts->header.stamp,
320 return mrpt::ros1bridge::fromROS(tx);
324 "[onNewSensor_PointCloud] robot pose %s",
325 robotPose.asString().c_str());
338 m_hist_obs_mtx.lock();
340 m_hist_obs.end(), TListObservations::value_type(timestamp, ipt));
341 m_hist_obs_mtx.unlock();
348 CTimeLoggerEntry tle(m_profiler,
"onDoPublish");
351 TListObservations obs;
353 CTimeLoggerEntry tle(m_profiler,
"onDoPublish.removingOld");
354 m_hist_obs_mtx.lock();
357 if (!m_hist_obs.empty())
359 const double last_time = m_hist_obs.rbegin()->first;
360 TListObservations::iterator it_first_valid =
361 m_hist_obs.lower_bound(last_time - m_time_window);
362 const size_t nToRemove =
363 std::distance(m_hist_obs.begin(), it_first_valid);
365 "[onDoPublish] Removing %u old entries, last_time=%lf",
366 static_cast<unsigned int>(nToRemove), last_time);
367 m_hist_obs.erase(m_hist_obs.begin(), it_first_valid);
371 m_hist_obs_mtx.unlock();
375 "Building local map with %u observations.",
376 static_cast<unsigned int>(obs.size()));
377 if (obs.empty())
return;
381 m_localmap_pts->clear();
382 mrpt::poses::CPose3D curRobotPose;
384 CTimeLoggerEntry tle2(m_profiler,
"onDoPublish.buildLocalMap");
393 geometry_msgs::TransformStamped tx;
395 m_frameid_reference, m_frameid_robot,
ros::Time(0),
400 curRobotPose = mrpt::ros1bridge::fromROS(tfx);
409 "[onDoPublish] Building local map relative to latest robot " 411 curRobotPose.asString().c_str());
415 for (TListObservations::const_iterator it = obs.begin();
416 it != obs.end(); ++it)
421 mrpt::poses::CPose3D relPose(mrpt::poses::UNINITIALIZED_POSE);
422 relPose.inverseComposeFrom(ipt.
robot_pose, curRobotPose);
425 m_localmap_pts->insertObservationPtr(ipt.
observation, relPose);
431 mrpt::maps::CPointsMap::Ptr filteredPts;
433 if (!m_filter_pipeline.empty())
439 filteredPts = mm.
point_layer(m_filter_output_layer_name);
443 filteredPts = m_localmap_pts;
449 sensor_msgs::PointCloud2 msg_pts;
450 msg_pts.header.frame_id = m_frameid_robot;
451 msg_pts.header.stamp =
ros::Time(obs.rbegin()->first);
454 std::dynamic_pointer_cast<mrpt::maps::CSimplePointsMap>(
458 mrpt::ros1bridge::toROS(*simplPts, msg_pts.header, msg_pts);
459 m_pub_local_map_pointcloud.
publish(msg_pts);
467 m_gui_win = mrpt::gui::CDisplayWindow3D::Create(
468 "LocalObstaclesNode", 800, 600);
469 mrpt::opengl::COpenGLScene::Ptr& scene =
470 m_gui_win->get3DSceneAndLock();
471 scene->insert(mrpt::opengl::CGridPlaneXY::Create());
473 mrpt::opengl::stock_objects::CornerXYZSimple(1.0, 4.0));
475 auto gl_obs = mrpt::opengl::CSetOfObjects::Create();
476 gl_obs->setName(
"obstacles");
477 scene->insert(gl_obs);
479 auto gl_rawpts = mrpt::opengl::CPointCloud::Create();
480 gl_rawpts->setName(
"raw_points");
481 gl_rawpts->setPointSize(1.0);
482 gl_rawpts->setColor_u8(TColor(0x00ff00));
483 scene->insert(gl_rawpts);
485 auto gl_pts = mrpt::opengl::CPointCloud::Create();
486 gl_pts->setName(
"final_points");
487 gl_pts->setPointSize(3.0);
488 gl_pts->setColor_u8(TColor(0x0000ff));
489 scene->insert(gl_pts);
491 m_gui_win->unlockAccess3DScene();
494 auto& scene = m_gui_win->get3DSceneAndLock();
495 auto gl_obs = mrpt::ptr_cast<mrpt::opengl::CSetOfObjects>::from(
496 scene->getByName(
"obstacles"));
500 auto glRawPts = mrpt::ptr_cast<mrpt::opengl::CPointCloud>::from(
501 scene->getByName(
"raw_points"));
503 auto glFinalPts = mrpt::ptr_cast<mrpt::opengl::CPointCloud>::from(
504 scene->getByName(
"final_points"));
506 for (
const auto& o : obs)
510 mrpt::poses::CPose3D relPose(mrpt::poses::UNINITIALIZED_POSE);
511 relPose.inverseComposeFrom(ipt.
robot_pose, curRobotPose);
513 mrpt::opengl::CSetOfObjects::Ptr gl_axis =
514 mrpt::opengl::stock_objects::CornerXYZSimple(0.9, 2.0);
515 gl_axis->setPose(relPose);
516 gl_obs->insert(gl_axis);
519 glRawPts->loadFromPointsMap(m_localmap_pts.get());
520 glFinalPts->loadFromPointsMap(filteredPts.get());
522 m_gui_win->unlockAccess3DScene();
523 m_gui_win->repaint();
531 : m_auxinit(argc, argv), m_nh(), m_localn(
"~")
534 m_localn.
param(
"show_gui", m_show_gui, m_show_gui);
537 "frameid_reference", m_frameid_reference, m_frameid_reference);
538 m_localn.
param(
"frameid_robot", m_frameid_robot, m_frameid_robot);
541 "topic_local_map_pointcloud", m_topic_local_map_pointcloud,
542 m_topic_local_map_pointcloud);
545 "source_topics_2dscan", m_source_topics_2dscan,
546 m_source_topics_2dscan);
548 "source_topics_pointclouds", m_source_topics_pointclouds,
549 m_source_topics_pointclouds);
551 m_localn.
param(
"time_window", m_time_window, m_time_window);
552 m_localn.
param(
"publish_period", m_publish_period, m_publish_period);
565 m_filter_output_layer_name =
568 !m_filter_output_layer_name.empty(),
569 "'filter_yaml_file' param also requires " 570 "'filter_output_layer_name'");
574 m_pub_local_map_pointcloud = m_nh.
advertise<sensor_msgs::PointCloud2>(
575 m_topic_local_map_pointcloud, 10);
579 size_t nSubsTotal = 0;
580 nSubsTotal += this->subscribeToMultipleTopics(
581 m_source_topics_2dscan, m_subs_2dlaser,
584 nSubsTotal += this->subscribeToMultipleTopics(
585 m_source_topics_pointclouds, m_subs_pointclouds,
589 "Total number of sensor subscriptions: %u\n",
590 static_cast<unsigned int>(nSubsTotal));
593 "*Error* It is mandatory to set at least one source topic for " 594 "sensory information!");
597 m_localmap_pts->insertionOptions.minDistBetweenLaserPoints = 0;
598 m_localmap_pts->insertionOptions.also_interpolate =
false;
608 int main(
int argc,
char** argv)
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
TAuxInitializer m_auxinit
Just to make sure ROS is init first.
std::string m_filter_output_layer_name
mp2p_icp output layer name
Generic container of pointcloud(s), extracted features and other maps.
std::vector< ros::Subscriber > m_subs_2dlaser
Subscriber to point cloud sensors.
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Builds a new layer with a decimated version of an input layer.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
LocalObstaclesNode(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
TAuxInitializer(int argc, char **argv)
mp2p_icp_filters::FilterPipeline m_filter_pipeline
ros::NodeHandle m_localn
"~"
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void publish(const boost::shared_ptr< M > &message) const
TListObservations m_hist_obs
static constexpr const char * PT_LAYER_RAW
mrpt::gui::CDisplayWindow3D::Ptr m_gui_win
#define ROS_ASSERT_MSG(cond,...)
void apply_filter_pipeline(const FilterPipeline &filters, mp2p_icp::metric_map_t &inOut)
void fromMsg(const A &, B &b)
CObservation::Ptr observation
void onDoPublish(const ros::TimerEvent &)
size_t subscribeToMultipleTopics(const std::string &lstTopics, std::vector< ros::Subscriber > &subs, CALLBACK_METHOD_TYPE cb)
Subscribe to a variable number of topics.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
FilterPipeline filter_pipeline_from_yaml_file(const std::string &filename, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
ros::Publisher m_pub_local_map_pointcloud
Subscriber to 2D laser scans.
mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t &name) const
mrpt::poses::CPose3D robot_pose
std::vector< ros::Subscriber > m_subs_pointclouds
tf2_ros::Buffer m_tf_buffer
ros::NodeHandle m_nh
The node handle.
std::vector< FilterBase::Ptr > FilterPipeline
void onNewSensor_Laser2D(const sensor_msgs::LaserScanConstPtr &scan)
uint32_t getNumSubscribers() const
ros::Timer m_timer_publish
std::multimap< double, TInfoPerTimeStep > TListObservations
void onNewSensor_PointCloud(const sensor_msgs::PointCloud2::ConstPtr &pts)