mrpt_rbpf_slam_wrapper.cpp
Go to the documentation of this file.
2 #include <mrpt/maps/CBeaconMap.h>
3 #include <mrpt/maps/COccupancyGridMap2D.h>
5 using mrpt::maps::CBeaconMap;
6 using mrpt::maps::COccupancyGridMap2D;
7 
8 namespace {
9 bool isFileExists(const std::string &name) {
10  std::ifstream f(name.c_str());
11  return f.good();
12 }
13 } // namespace
14 
15 namespace mrpt_rbpf_slam {
17  mrpt_bridge::convert(ros::Time(0), timeLastUpdate_);
18 }
19 
21  ROS_INFO("READ PARAM FROM LAUNCH FILE");
22  nh_p.param<double>("rawlog_play_delay", rawlog_play_delay_, 0.1);
23  ROS_INFO("rawlog_play_delay: %f", rawlog_play_delay_);
24 
25  nh_p.getParam("rawlog_filename", rawlog_filename_);
26  ROS_INFO("rawlog_filename: %s", rawlog_filename_.c_str());
27 
28  nh_p.getParam("ini_filename", ini_filename_);
29  ROS_INFO("ini_filename: %s", ini_filename_.c_str());
30 
31  nh_p.param<std::string>("global_frame_id", global_frame_id_, "map");
32  ROS_INFO("global_frame_id: %s", global_frame_id_.c_str());
33 
34  nh_p.param<std::string>("odom_frame_id", odom_frame_id_, "odom");
35  ROS_INFO("odom_frame_id: %s", odom_frame_id_.c_str());
36 
37  nh_p.param<std::string>("base_frame_id", base_frame_id_, "base_link");
38  ROS_INFO("base_frame_id: %s", base_frame_id_.c_str());
39 
40  nh_p.param<std::string>("sensor_source", sensor_source_, "scan");
41  ROS_INFO("sensor_source: %s", sensor_source_.c_str());
42 
44  if (!loadOptions(nh_p, options)) {
45  ROS_ERROR("Not able to read all parameters!");
46  return false;
47  }
48  initSlam(std::move(options));
49  return true;
50 }
51 
53  // get parameters from ini file
54  if (!isFileExists(ini_filename_)) {
55  ROS_ERROR_STREAM("CAN'T READ INI FILE" << ini_filename_);
56  return false;
57  }
58 
60 
61  // read rawlog file if it exists
62  if (isFileExists(rawlog_filename_)) {
63  ROS_WARN_STREAM("PLAY FROM RAWLOG FILE: " << rawlog_filename_);
65  rawlog_play_ = true;
66  }
67 
69  // publish grid map
70  pub_map_ = nh.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
71  pub_metadata_ = nh.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
72  // robot pose
74  nh.advertise<geometry_msgs::PoseArray>("particlecloud", 1, true);
75  // ro particles poses
77  nh.advertise<geometry_msgs::PoseArray>("particlecloud_beacons", 1, true);
79  nh.advertise<visualization_msgs::MarkerArray>("/beacons_viz", 1);
80 
81  // read sensor topics
82  std::vector<std::string> lstSources;
83  mrpt::system::tokenize(sensor_source_, " ,\t\n", lstSources);
84  ROS_ASSERT_MSG(!lstSources.empty(),
85  "*Fatal*: At least one sensor source must be provided in "
86  "~sensor_sources (e.g. "
87  "\"scan\" or \"beacon\")");
88 
90  sensorSub_.resize(lstSources.size());
91  for (size_t i = 0; i < lstSources.size(); i++) {
92  if (lstSources[i].find("scan") != std::string::npos) {
93  sensorSub_[i] =
94  nh.subscribe(lstSources[i], 1, &PFslamWrapper::laserCallback, this);
95  } else {
96  sensorSub_[i] =
97  nh.subscribe(lstSources[i], 1, &PFslamWrapper::callbackBeacon, this);
98  }
99  }
100 
101  mapBuilder_ = mrpt::slam::CMetricMapBuilderRBPF(options_.rbpfMappingOptions_);
102  init3Dwindow();
103  return true;
104 }
105 
107  mrpt::obs::CObservationOdometry::Ptr &odometry,
108  const std_msgs::Header &_msg_header) {
109  mrpt::poses::CPose3D poseOdom;
110  if (this->waitForTransform(poseOdom, odom_frame_id_, base_frame_id_,
111  _msg_header.stamp, ros::Duration(1))) {
112  odometry = mrpt::obs::CObservationOdometry::Create();
113  odometry->sensorLabel = odom_frame_id_;
114  odometry->hasEncodersInfo = false;
115  odometry->hasVelocities = false;
116  odometry->odometry.x() = poseOdom.x();
117  odometry->odometry.y() = poseOdom.y();
118  odometry->odometry.phi() = poseOdom.yaw();
119  }
120 }
121 
123  mrpt::poses::CPose3D &des, const std::string &target_frame,
124  const std::string &source_frame, const ros::Time &time,
125  const ros::Duration &timeout, const ros::Duration &polling_sleep_duration) {
126  tf::StampedTransform transform;
127  try {
128  listenerTF_.waitForTransform(target_frame, source_frame, time, timeout,
129  polling_sleep_duration);
130  listenerTF_.lookupTransform(target_frame, source_frame, time, transform);
131  } catch (tf::TransformException ex) {
132  ROS_ERROR("Failed to get transform target_frame (%s) to source_frame (%s). "
133  "TransformException: %s",
134  target_frame.c_str(), source_frame.c_str(), ex.what());
135  return false;
136  }
137  mrpt_bridge::convert(transform, des);
138  return true;
139 }
140 
141 void PFslamWrapper::laserCallback(const sensor_msgs::LaserScan &msg) {
142  using namespace mrpt::maps;
143  using namespace mrpt::obs;
144  CObservation2DRangeScan::Ptr laser = CObservation2DRangeScan::Create();
145 
146  if (laser_poses_.find(msg.header.frame_id) == laser_poses_.end()) {
147  updateSensorPose(msg.header.frame_id);
148  } else {
149  mrpt::poses::CPose3D pose = laser_poses_[msg.header.frame_id];
150  mrpt_bridge::convert(msg, laser_poses_[msg.header.frame_id], *laser);
151 
152  sensory_frame_ = CSensoryFrame::Create();
153  CObservationOdometry::Ptr odometry;
154  odometryForCallback(odometry, msg.header);
155 
156  CObservation::Ptr obs = CObservation::Ptr(laser);
157  sensory_frame_->insert(obs);
158  observation(sensory_frame_, odometry);
159  timeLastUpdate_ = sensory_frame_->getObservationByIndex(0)->timestamp;
160 
161  tictac_.Tic();
162  mapBuilder_.processActionObservation(*action_, *sensory_frame_);
163  t_exec_ = tictac_.Tac();
164  ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec_);
165  publishMapPose();
166  run3Dwindow();
167  publishTF();
168  }
169 }
170 
172  const mrpt_msgs::ObservationRangeBeacon &msg) {
173  using namespace mrpt::maps;
174  using namespace mrpt::obs;
175 
176  CObservationBeaconRanges::Ptr beacon = CObservationBeaconRanges::Create();
177  if (beacon_poses_.find(msg.header.frame_id) == beacon_poses_.end()) {
178  updateSensorPose(msg.header.frame_id);
179  } else {
180  mrpt_bridge::convert(msg, beacon_poses_[msg.header.frame_id], *beacon);
181 
182  sensory_frame_ = CSensoryFrame::Create();
183  CObservationOdometry::Ptr odometry;
184  odometryForCallback(odometry, msg.header);
185 
186  CObservation::Ptr obs = CObservation::Ptr(beacon);
187  sensory_frame_->insert(obs);
188  observation(sensory_frame_, odometry);
189  timeLastUpdate_ = sensory_frame_->getObservationByIndex(0)->timestamp;
190 
191  tictac_.Tic();
192  mapBuilder_.processActionObservation(*action_, *sensory_frame_);
193  t_exec_ = tictac_.Tac();
194  ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec_);
195 
196  publishMapPose();
197  run3Dwindow();
198  }
199 }
200 
202  // if I received new grid maps from 2D laser scan sensors
203  metric_map_ = mapBuilder_.mapPDF.getCurrentMostLikelyMetricMap();
204  mapBuilder_.mapPDF.getEstimatedPosePDF(curPDF);
205  // publish map
206 
207  COccupancyGridMap2D *grid = nullptr;
208  CBeaconMap *bm = nullptr;
209 #if MRPT_VERSION >= 0x199
210  if (metric_map_->countMapsByClass<COccupancyGridMap2D>())
211  grid = metric_map_->mapByClass<COccupancyGridMap2D>().get();
212  bm = metric_map_->mapByClass<CBeaconMap>().get();
213 #else
214  if (metric_map_->m_gridMaps.size())
215  grid = metric_map_->m_gridMaps[0].get();
216  bm = metric_map_->getMapByClass<CBeaconMap>().get();
217 #endif
218 
219  if (grid) {
220  // publish map
221  nav_msgs::OccupancyGrid msg;
222  mrpt_bridge::convert(*grid, msg);
223  pub_map_.publish(msg);
224  pub_metadata_.publish(msg.info);
225  }
226 
227  // if I received new beacon (range only) map
228  if (bm) {
229  mrpt::opengl::CSetOfObjects::Ptr objs;
230 
231  objs = mrpt::opengl::CSetOfObjects::Create();
232  // Get th map as the set of 3D objects
233  bm->getAs3DObject(objs);
234 
235  geometry_msgs::PoseArray poseArrayBeacons;
236  poseArrayBeacons.header.frame_id = global_frame_id_;
237  poseArrayBeacons.header.stamp = ros::Time::now();
238 
239  // Count the number of beacons
240  unsigned int objs_counter = 0;
241  while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter)) {
242  objs_counter++;
243  }
244  poseArrayBeacons.poses.resize(objs_counter);
245  mrpt::opengl::CEllipsoid::Ptr beacon_particle;
246 
247  for (size_t i = 0; i < objs_counter; i++) {
248  beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
249  mrpt_bridge::convert(mrpt::poses::CPose3D(beacon_particle->getPose()),
250  poseArrayBeacons.poses[i]);
251  viz_beacons_.push_back(beacon_particle);
252  }
253  pub_particles_beacons_.publish(poseArrayBeacons);
254  vizBeacons();
255  viz_beacons_.clear();
256  }
257 
258  // publish pose
259  geometry_msgs::PoseArray poseArray;
260  poseArray.header.frame_id = global_frame_id_;
261  poseArray.header.stamp = ros::Time::now();
262  poseArray.poses.resize(curPDF.particlesCount());
263  for (size_t i = 0; i < curPDF.particlesCount(); i++) {
264  const auto p = mrpt::poses::CPose3D(curPDF.getParticlePose(i));
265  mrpt_bridge::convert(p, poseArray.poses[i]);
266  }
267 
268  pub_particles_.publish(poseArray);
269 }
270 
272  if (viz_beacons_.size() == 0) {
273  return;
274  }
275  visualization_msgs::MarkerArray ma;
276  visualization_msgs::Marker marker;
277 
278  marker.header.frame_id = "/map";
279 
280  marker.id = 0;
281  marker.type = visualization_msgs::Marker::SPHERE;
282  marker.action = visualization_msgs::Marker::ADD;
283  marker.lifetime = ros::Duration(1);
284  marker.pose.position.x = 0;
285  marker.pose.position.y = 0;
286  marker.pose.position.z = 0;
287  marker.pose.orientation.x = 0.0;
288  marker.pose.orientation.y = 0.0;
289  marker.pose.orientation.z = 0.0;
290  marker.pose.orientation.w = 1.0;
291  marker.scale.x = 0.12;
292  marker.scale.y = 0.12;
293  marker.scale.z = 0.12;
294  marker.color.a = 1.0;
295  marker.color.r = 1.0;
296  marker.color.g = 0.0;
297 
298  for (unsigned int i = 0; i < viz_beacons_.size(); i++) {
299  mrpt::poses::CPose3D meanPose(viz_beacons_[i]->getPose());
300  marker.type = visualization_msgs::Marker::SPHERE;
301 
302  marker.pose.position.x = meanPose.x();
303  marker.pose.position.y = meanPose.y();
304  marker.pose.position.z = meanPose.z();
305  marker.color.r = 1.0;
306  marker.color.g = 0.0;
307  marker.color.b = 0.0;
308 
309  ma.markers.push_back(marker);
310  marker.id++;
311 
312  marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
313  marker.text = std::to_string(i);
314 
315  marker.pose.position.x = meanPose.x();
316  marker.pose.position.y = meanPose.y();
317  marker.pose.position.z = meanPose.z() + 0.12;
318  marker.color.r = 1.0;
319  marker.color.g = 1.0;
320  marker.color.b = 1.0;
321  // marker.scale.z = 1;
322  ma.markers.push_back(marker);
323  marker.id++;
324  }
325 
327 }
328 
329 void PFslamWrapper::updateSensorPose(const std::string &frame_id) {
330  mrpt::poses::CPose3D pose;
331  tf::StampedTransform transform;
332  try {
334  transform);
335 
336  tf::Vector3 translation = transform.getOrigin();
337  tf::Quaternion quat = transform.getRotation();
338  pose.x() = translation.x();
339  pose.y() = translation.y();
340  pose.z() = translation.z();
341  tf::Matrix3x3 Rsrc(quat);
342  mrpt::math::CMatrixDouble33 Rdes;
343  for (int c = 0; c < 3; c++)
344  for (int r = 0; r < 3; r++)
345  Rdes(r, c) = Rsrc.getRow(r)[c];
346  pose.setRotationMatrix(Rdes);
347  laser_poses_[frame_id] = pose;
348  beacon_poses_[frame_id] = pose;
349  } catch (tf::TransformException ex) {
350  ROS_ERROR("%s", ex.what());
351  ros::Duration(1.0).sleep();
352  }
353 }
354 
356  if (rawlog_play_ == false) {
357  return false;
358  } else {
359  for (unsigned int i = 0; i < data_.size(); i++) {
360  if (ros::ok()) {
361  tictac_.Tic();
362  mapBuilder_.processActionObservation(data_[i].first, data_[i].second);
363  t_exec_ = tictac_.Tac();
364  ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec_);
365 
367 
368  metric_map_ = mapBuilder_.mapPDF.getCurrentMostLikelyMetricMap();
369  mapBuilder_.mapPDF.getEstimatedPosePDF(curPDF);
370 
371  COccupancyGridMap2D *grid = nullptr;
372  CBeaconMap *bm = nullptr;
373 #if MRPT_VERSION >= 0x199
374  if (metric_map_->countMapsByClass<COccupancyGridMap2D>())
375  grid = metric_map_->mapByClass<COccupancyGridMap2D>().get();
376  bm = metric_map_->mapByClass<CBeaconMap>().get();
377 #else
378  if (metric_map_->m_gridMaps.size())
379  grid = metric_map_->m_gridMaps[0].get();
380  bm = metric_map_->getMapByClass<CBeaconMap>().get();
381 #endif
382 
383  // if I received new grid maps from 2D laser scan sensors
384  if (grid) {
385  nav_msgs::OccupancyGrid msg;
386  // if we have new map for current sensor update it
387  mrpt_bridge::convert(*grid, msg);
388  pub_map_.publish(msg);
389  pub_metadata_.publish(msg.info);
390  }
391 
392  // if I received new beacon (range only) map
393  if (bm) {
394  mrpt::opengl::CSetOfObjects::Ptr objs;
395  objs = mrpt::opengl::CSetOfObjects::Create();
396  bm->getAs3DObject(objs);
397 
398  geometry_msgs::PoseArray poseArrayBeacons;
399  poseArrayBeacons.header.frame_id = global_frame_id_;
400  poseArrayBeacons.header.stamp = ros::Time::now();
401 
402  unsigned int objs_counter = 0;
403  while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter)) {
404  objs_counter++;
405  }
406  poseArrayBeacons.poses.resize(objs_counter);
407  mrpt::opengl::CEllipsoid::Ptr beacon_particle;
408 
409  for (size_t i = 0; i < objs_counter; i++) {
410  beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
411  mrpt_bridge::convert(
412  mrpt::poses::CPose3D(beacon_particle->getPose()),
413  poseArrayBeacons.poses[i]);
414  viz_beacons_.push_back(beacon_particle);
415  }
416  pub_particles_beacons_.publish(poseArrayBeacons);
417  vizBeacons();
418  viz_beacons_.clear();
419  }
420 
421  // publish pose
422  geometry_msgs::PoseArray poseArray;
423  poseArray.header.frame_id = global_frame_id_;
424  poseArray.header.stamp = ros::Time::now();
425  poseArray.poses.resize(curPDF.particlesCount());
426  for (size_t i = 0; i < curPDF.particlesCount(); i++) {
427  const auto p = mrpt::poses::CPose3D(curPDF.getParticlePose(i));
428  mrpt_bridge::convert(p, poseArray.poses[i]);
429  }
430 
431  pub_particles_.publish(poseArray);
432  }
433  ros::spinOnce();
434  run3Dwindow();
435  }
436  }
437  // if there is mrpt_gui it will wait until push any key in order to close the
438  // window
439  if (win3D_)
440  win3D_->waitForKey();
441  return true;
442 }
443 
445  // Most of this code was copy and pase from ros::amcl
446  mrpt::poses::CPose3D robotPose;
447  mapBuilder_.mapPDF.getEstimatedPosePDF(curPDF);
448 
449  curPDF.getMean(robotPose);
450 
451  tf::Stamped<tf::Pose> odom_to_map;
452  tf::Transform tmp_tf;
453  ros::Time stamp;
454  mrpt_bridge::convert(timeLastUpdate_, stamp);
455  mrpt_bridge::convert(robotPose, tmp_tf);
456 
457  try {
458  tf::Stamped<tf::Pose> tmp_tf_stamped(tmp_tf.inverse(), stamp,
460  listenerTF_.transformPose(odom_frame_id_, tmp_tf_stamped, odom_to_map);
461  } catch (tf::TransformException ex) {
462  ROS_ERROR("Failed to subtract global_frame (%s) from odom_frame (%s). "
463  "TransformException: %s",
464  global_frame_id_.c_str(), odom_frame_id_.c_str(), ex.what());
465  return;
466  }
467 
468  tf::Transform latest_tf_ =
469  tf::Transform(tf::Quaternion(odom_to_map.getRotation()),
470  tf::Point(odom_to_map.getOrigin()));
471 
472  // We want to send a transform that is good up until a
473  // tolerance time so that odom can be used
474 
475  ros::Duration transform_tolerance_(0.5);
476  ros::Time transform_expiration = (stamp + transform_tolerance_);
477  tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
478  transform_expiration, global_frame_id_,
480  tf_broadcaster_.sendTransform(tmp_tf_stamped);
481 }
482 
483 } // namespace mrpt_rbpf_slam
std::string global_frame_id_
/map frame
tf::TransformListener listenerTF_
transform listener
void odometryForCallback(mrpt::obs::CObservationOdometry::Ptr &odometry, const std_msgs::Header &msg_header)
Get the odometry for received observation.
std::vector< ros::Subscriber > sensorSub_
list of sensors topics
mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions rbpfMappingOptions_
options for SLAM from ini file
void observation(const mrpt::obs::CSensoryFrame::ConstPtr sensory_frame, const mrpt::obs::CObservationOdometry::ConstPtr odometry)
Calculate the actions from odometry model for current observation.
void publish(const boost::shared_ptr< M > &message) const
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string rawlog_filename_
name of rawlog file
std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame > > data_
void laserCallback(const sensor_msgs::LaserScan &msg)
Callback function for the laser scans.
ros::Publisher beacon_viz_pub_
publishers for map and pose particles
mrpt::poses::CPose3DPDFParticles curPDF
current robot pose
std::string odom_frame_id_
/odom frame
bool sleep() const
void vizBeacons()
Correct visualization for ro slam.
bool getParams(const ros::NodeHandle &nh_p)
Read the parameters from launch file.
float t_exec_
the time which take one SLAM update execution
void publishMapPose()
Publish beacon or grid map and robot pose.
std::map< std::string, mrpt::poses::CPose3D > beacon_poses_
beacon poses with respect to the map
bool waitForTransform(mrpt::poses::CPose3D &des, const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01))
Wait for transform between odometry frame and the robot frame.
bool init(ros::NodeHandle &nh)
Initialize publishers subscribers and RBPF slam.
mrpt::gui::CDisplayWindow3D::Ptr win3D_
MRPT window.
TFSIMD_FORCE_INLINE const Vector3 & getRow(int i) const
struct mrpt_rbpf_slam::PFslam::Options options_
mrpt::obs::CSensoryFrame::Ptr sensory_frame_
observations
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
void readIniFile(const std::string &ini_filename)
Read ini file.
mrpt::slam::CMetricMapBuilderRBPF mapBuilder_
map builder
void updateSensorPose(const std::string &frame_id)
Update the pose of the sensor with respect to the robot.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void initSlam(Options options)
initialize the SLAM
TFSIMD_FORCE_INLINE const tfScalar & z() const
void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon &msg)
Callback function for the beacons.
#define ROS_INFO(...)
options
mrpt::obs::CActionCollection::Ptr action_
actions
std::string sensor_source_
2D laser scans
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_ASSERT_MSG(cond,...)
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & y() const
void sendTransform(const StampedTransform &transform)
Transform inverse() const
void readRawlog(const std::string &rawlog_filename, std::vector< std::pair< mrpt::obs::CActionCollection, mrpt::obs::CSensoryFrame >> &data)
Read pairs of actions and observations from rawlog file.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double rawlog_play_delay_
delay of replay from rawlog file
#define ROS_WARN_STREAM(args)
bool loadOptions(const ros::NodeHandle &nh, PFslam::Options &options)
Definition: options.cpp:91
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
mrpt::system::TTimeStamp timeLastUpdate_
last update of the pose and map
const mrpt::maps::CMultiMetricMap * metric_map_
receive map after iteration of SLAM to metric map
bool rawlog_play_
true if rawlog file exists
std::map< std::string, mrpt::poses::CPose3D > laser_poses_
laser scan poses with respect to the map
std::string ini_filename_
name of ini file
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
Quaternion getRotation() const
bool getParam(const std::string &key, std::string &s) const
tf::TransformBroadcaster tf_broadcaster_
transform broadcaster
static Time now()
std::vector< mrpt::opengl::CEllipsoid::Ptr > viz_beacons_
std::string base_frame_id_
robot frame
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
r
#define ROS_ERROR(...)


mrpt_rbpf_slam
Author(s): Vladislav Tananaev
autogenerated on Thu Jun 6 2019 19:37:56