mcl_3dl.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2020, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <algorithm>
31 #include <cassert>
32 #include <cmath>
33 #include <limits>
34 #include <map>
35 #include <memory>
36 #include <string>
37 #include <utility>
38 #include <vector>
39 
40 #include <Eigen/Core>
41 
42 #include <boost/chrono.hpp>
43 #include <boost/shared_ptr.hpp>
44 
45 #include <ros/ros.h>
46 
47 #include <sensor_msgs/PointCloud2.h>
49 #include <nav_msgs/Odometry.h>
50 #include <sensor_msgs/Imu.h>
51 #include <geometry_msgs/PoseArray.h>
52 #include <geometry_msgs/PoseWithCovarianceStamped.h>
53 #include <geometry_msgs/TransformStamped.h>
54 #include <visualization_msgs/MarkerArray.h>
55 #include <mcl_3dl_msgs/ResizeParticle.h>
56 #include <mcl_3dl_msgs/Status.h>
57 #include <mcl_3dl_msgs/LoadPCD.h>
58 #include <std_srvs/Trigger.h>
60 
65 
67 #include <pcl/point_types.h>
68 #include <pcl_ros/point_cloud.h>
69 #include <pcl_ros/transforms.h>
70 #include <pcl/conversions.h>
71 #include <pcl/filters/voxel_grid.h>
72 #include <pcl/kdtree/kdtree.h>
73 #include <pcl/kdtree/kdtree_flann.h>
74 
75 #include <mcl_3dl/chunked_kdtree.h>
76 #include <mcl_3dl/cloud_accum.h>
77 #include <mcl_3dl/filter.h>
78 #include <mcl_3dl/filter_vec3.h>
86 #include <mcl_3dl/nd.h>
88 #include <mcl_3dl/parameters.h>
89 #include <mcl_3dl/pf.h>
93 #include <mcl_3dl/point_types.h>
94 #include <mcl_3dl/quat.h>
95 #include <mcl_3dl/raycast.h>
96 #include <mcl_3dl/state_6dof.h>
97 #include <mcl_3dl/vec3.h>
98 
100 
101 namespace mcl_3dl
102 {
104 {
105 protected:
107  std::shared_ptr<pf::ParticleFilter<State6DOF, float, ParticleWeightedMeanQuat, std::default_random_engine>> pf_;
108 
109  class MyPointRepresentation : public pcl::PointRepresentation<PointType>
110  {
111  using pcl::PointRepresentation<PointType>::nr_dimensions_;
112 
113  public:
115  {
116  nr_dimensions_ = 3;
117  trivial_ = true;
118  }
119 
120  virtual void copyToFloatArray(const PointType& p, float* out) const
121  {
122  out[0] = p.x;
123  out[1] = p.y;
124  out[2] = p.z;
125  }
126  };
127  void cbMapcloud(const sensor_msgs::PointCloud2::ConstPtr& msg)
128  {
129  ROS_INFO("map received");
130  pcl::PointCloud<PointType>::Ptr pc_tmp(new pcl::PointCloud<PointType>);
131  if (!mcl_3dl::fromROSMsg(*msg, *pc_tmp))
132  {
133  has_map_ = false;
134  return;
135  }
136  const ros::Time map_stamp = (msg->header.stamp != ros::Time()) ? msg->header.stamp : ros::Time::now();
137  pcl_conversions::toPCL(map_stamp, pc_tmp->header.stamp);
138 
139  loadMapCloud(pc_tmp);
140  }
141  void cbMapcloudUpdate(const sensor_msgs::PointCloud2::ConstPtr& msg)
142  {
143  ROS_INFO("map_update received");
144  pcl::PointCloud<PointType>::Ptr pc_tmp(new pcl::PointCloud<PointType>);
145  if (!mcl_3dl::fromROSMsg(*msg, *pc_tmp))
146  return;
147 
148  pc_update_.reset(new pcl::PointCloud<PointType>);
149  pcl::VoxelGrid<PointType> ds;
150  ds.setInputCloud(pc_tmp);
152  ds.filter(*pc_update_);
153  }
154 
155  void cbPosition(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
156  {
157  const double len2 =
158  msg->pose.pose.orientation.x * msg->pose.pose.orientation.x +
159  msg->pose.pose.orientation.y * msg->pose.pose.orientation.y +
160  msg->pose.pose.orientation.z * msg->pose.pose.orientation.z +
161  msg->pose.pose.orientation.w * msg->pose.pose.orientation.w;
162  if (std::abs(len2 - 1.0) > 0.1)
163  {
164  ROS_ERROR("Discarded invalid initialpose. The orientation must be unit quaternion.");
165  return;
166  }
167 
168  geometry_msgs::PoseStamped pose_in, pose;
169  pose_in.header = msg->header;
170  pose_in.pose = msg->pose.pose;
171  try
172  {
173  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
174  params_.frame_ids_["map"], pose_in.header.frame_id, pose_in.header.stamp, ros::Duration(1.0));
175  tf2::doTransform(pose_in, pose, trans);
176  }
177  catch (tf2::TransformException& e)
178  {
179  return;
180  }
181  const State6DOF mean(Vec3(pose.pose.position.x, pose.pose.position.y, pose.pose.position.z),
182  Quat(pose.pose.orientation.x,
183  pose.pose.orientation.y,
184  pose.pose.orientation.z,
185  pose.pose.orientation.w));
186  const MultivariateNoiseGenerator<float> noise_gen(mean, msg->pose.covariance);
187  pf_->initUsingNoiseGenerator(noise_gen);
188 
189  pc_update_.reset();
190  auto integ_reset_func = [](State6DOF& s)
191  {
192  s.odom_err_integ_lin_ = Vec3();
193  s.odom_err_integ_ang_ = Vec3();
194  };
195  pf_->predict(integ_reset_func);
196 
198  }
199 
200  void cbOdom(const nav_msgs::Odometry::ConstPtr& msg)
201  {
202  odom_ =
203  State6DOF(
204  Vec3(msg->pose.pose.position.x,
205  msg->pose.pose.position.y,
206  msg->pose.pose.position.z),
207  Quat(msg->pose.pose.orientation.x,
208  msg->pose.pose.orientation.y,
209  msg->pose.pose.orientation.z,
210  msg->pose.pose.orientation.w));
211  if (!has_odom_)
212  {
213  odom_prev_ = odom_;
214  odom_last_ = msg->header.stamp;
215  has_odom_ = true;
216  return;
217  }
218  const float dt = (msg->header.stamp - odom_last_).toSec();
219  if (dt < 0.0 || dt > 5.0)
220  {
221  ROS_WARN("Detected time jump in odometry. Resetting.");
222  has_odom_ = false;
223  return;
224  }
225  else if (dt > 0.05)
226  {
227  motion_prediction_model_->setOdoms(odom_prev_, odom_, dt);
228  auto prediction_func = [this](State6DOF& s)
229  {
230  motion_prediction_model_->predict(s);
231  };
232  pf_->predict(prediction_func);
233  odom_last_ = msg->header.stamp;
234  odom_prev_ = odom_;
235  }
236  if (params_.fake_imu_)
237  {
238  const Vec3 accel = odom_.rot_ * Vec3(0.0, 0.0, 1.0);
239  sensor_msgs::Imu::Ptr imu(new sensor_msgs::Imu);
240  imu->header = msg->header;
241  imu->linear_acceleration.x = accel.x_;
242  imu->linear_acceleration.y = accel.y_;
243  imu->linear_acceleration.z = accel.z_;
244  imu->orientation = msg->pose.pose.orientation;
245  cbImu(imu);
246  }
247  }
248  void cbCloud(const sensor_msgs::PointCloud2::ConstPtr& msg)
249  {
250  status_ = mcl_3dl_msgs::Status();
251  status_.header.stamp = ros::Time::now();
252  status_.status = mcl_3dl_msgs::Status::NORMAL;
253  status_.error = mcl_3dl_msgs::Status::ERROR_NORMAL;
254  status_.convergence_status = mcl_3dl_msgs::Status::CONVERGENCE_STATUS_NORMAL;
255 
256  if (!has_map_)
257  return;
258 
259  accum_->push(
260  msg->header.frame_id,
261  msg,
262  std::bind(&MCL3dlNode::measure, this),
263  std::bind(&MCL3dlNode::accumCloud, this, std::placeholders::_1),
264  std::bind(&MCL3dlNode::accumClear, this));
265  }
266 
267  void accumClear()
268  {
269  pc_local_accum_.reset(new pcl::PointCloud<PointType>);
270  pc_local_accum_->header.frame_id = params_.frame_ids_["odom"];
271  pc_accum_header_.clear();
272  }
273 
274  bool accumCloud(const sensor_msgs::PointCloud2::ConstPtr& msg)
275  {
276  sensor_msgs::PointCloud2 pc_bl;
277  try
278  {
279  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
280  params_.frame_ids_["odom"], msg->header.frame_id, msg->header.stamp, ros::Duration(0.1));
281  tf2::doTransform(*msg, pc_bl, trans);
282  }
283  catch (tf2::TransformException& e)
284  {
285  ROS_INFO("Failed to transform pointcloud: %s", e.what());
286  return false;
287  }
288  pcl::PointCloud<PointType>::Ptr pc_tmp(new pcl::PointCloud<PointType>);
289  if (!mcl_3dl::fromROSMsg(pc_bl, *pc_tmp))
290  {
291  ROS_INFO("Failed to convert pointcloud");
292  return false;
293  }
294 
295  for (auto& p : pc_tmp->points)
296  {
297  p.label = pc_accum_header_.size();
298  }
299  *pc_local_accum_ += *pc_tmp;
300  pc_accum_header_.push_back(msg->header);
301  return true;
302  }
303 
304  void measure()
305  {
306  cnt_measure_++;
307  if (cnt_measure_ % static_cast<size_t>(params_.skip_measure_) != 0)
308  {
309  return;
310  }
311 
312  if (pc_accum_header_.empty())
313  {
314  ROS_ERROR("MCL measure function is called without available pointcloud");
315  return;
316  }
317  const std_msgs::Header& header = pc_accum_header_.back();
318 
319  try
320  {
321  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
322  params_.frame_ids_["base_link"],
323  pc_local_accum_->header.frame_id,
324  header.stamp, ros::Duration(0.1));
325 
326  const Eigen::Affine3f trans_eigen =
327  Eigen::Translation3f(
328  trans.transform.translation.x,
329  trans.transform.translation.y,
330  trans.transform.translation.z) *
331  Eigen::Quaternionf(
332  trans.transform.rotation.w,
333  trans.transform.rotation.x,
334  trans.transform.rotation.y,
335  trans.transform.rotation.z);
336  pcl::transformPointCloud(*pc_local_accum_, *pc_local_accum_, trans_eigen);
337  }
338  catch (tf2::TransformException& e)
339  {
340  ROS_INFO("Failed to transform pointcloud: %s", e.what());
341  return;
342  }
343  std::vector<Vec3> origins;
344  for (auto& h : pc_accum_header_)
345  {
346  try
347  {
348  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
349  params_.frame_ids_["base_link"], header.stamp, h.frame_id, h.stamp, params_.frame_ids_["odom"]);
350  origins.push_back(Vec3(trans.transform.translation.x,
351  trans.transform.translation.y,
352  trans.transform.translation.z));
353  }
354  catch (tf2::TransformException& e)
355  {
356  ROS_INFO("Failed to transform pointcloud: %s", e.what());
357  return;
358  }
359  }
360 
361  const auto ts = boost::chrono::high_resolution_clock::now();
362 
363  pcl::PointCloud<PointType>::Ptr pc_local_full(new pcl::PointCloud<PointType>);
364  pcl::VoxelGrid<PointType> ds;
365  ds.setInputCloud(pc_local_accum_);
367  ds.filter(*pc_local_full);
368 
369  std::map<std::string, pcl::PointCloud<PointType>::Ptr> pc_locals;
370  for (auto& lm : lidar_measurements_)
371  {
372  lm.second->setGlobalLocalizationStatus(
373  params_.num_particles_, pf_->getParticleSize());
374 
376  {
377  const State6DOF prev_mean = pf_->expectation();
378  const float cov_ratio = std::max(0.1f, static_cast<float>(params_.num_particles_) / pf_->getParticleSize());
379  const std::vector<State6DOF> prev_cov = pf_->covariance(1.0, cov_ratio);
380  auto sampler = std::dynamic_pointer_cast<PointCloudSamplerWithNormal<PointType>>(lm.second->getRandomSampler());
381  sampler->setParticleStatistics(prev_mean, prev_cov);
382  }
383  pc_locals[lm.first] = lm.second->filter(pc_local_full);
384  }
385 
386  if (pc_locals["likelihood"]->size() == 0)
387  {
388  ROS_ERROR("All points are filtered out. Failed to localize.");
389  status_.error = mcl_3dl_msgs::Status::ERROR_POINTS_NOT_FOUND;
391  return;
392  }
393 
394  if (pc_locals["beam"] && pc_locals["beam"]->size() == 0)
395  {
396  ROS_DEBUG("All beam points are filtered out. Skipping beam model.");
397  }
398 
399  float match_ratio_min = 1.0;
400  float match_ratio_max = 0.0;
403  auto measure_func = [this, &pc_locals,
404  &origins,
405  &odom_error_lin_nd,
406  &match_ratio_min, &match_ratio_max](const State6DOF& s) -> float
407  {
408  float likelihood = 1;
409  std::map<std::string, float> qualities;
410  for (auto& lm : lidar_measurements_)
411  {
412  const LidarMeasurementResult result = lm.second->measure(
413  kdtree_, pc_locals[lm.first], origins, s);
414  likelihood *= result.likelihood;
415  qualities[lm.first] = result.quality;
416  }
417  if (match_ratio_min > qualities["likelihood"])
418  match_ratio_min = qualities["likelihood"];
419  if (match_ratio_max < qualities["likelihood"])
420  match_ratio_max = qualities["likelihood"];
421 
422  // odometry error integration
423  const float odom_error =
424  odom_error_lin_nd(s.odom_err_integ_lin_.norm());
425  return likelihood * odom_error;
426  };
427  pf_->measure(measure_func);
428 
429  if (static_cast<int>(pf_->getParticleSize()) > params_.num_particles_)
430  {
431  auto bias_func = [](const State6DOF& s, float& p_bias) -> void
432  {
433  p_bias = 1.0;
434  };
435  pf_->bias(bias_func);
436  }
437  else
438  {
441  auto bias_func = [this, &nl_lin, &nl_ang](const State6DOF& s, float& p_bias) -> void
442  {
443  const float lin_diff = (s.pos_ - state_prev_.pos_).norm();
444  Vec3 axis;
445  float ang_diff;
446  (s.rot_ * state_prev_.rot_.inv()).getAxisAng(axis, ang_diff);
447  p_bias = nl_lin(lin_diff) * nl_ang(ang_diff) + 1e-6;
448  assert(std::isfinite(p_bias));
449  };
450  pf_->bias(bias_func);
451  }
452  auto e = pf_->expectationBiased();
453  const auto e_max = pf_->max();
454 
455  assert(std::isfinite(e.pos_.x_));
456  assert(std::isfinite(e.pos_.y_));
457  assert(std::isfinite(e.pos_.z_));
458  assert(std::isfinite(e.rot_.x_));
459  assert(std::isfinite(e.rot_.y_));
460  assert(std::isfinite(e.rot_.z_));
461  assert(std::isfinite(e.rot_.w_));
462 
463  e.rot_.normalize();
464 
465  if (lidar_measurements_["beam"])
466  {
467  visualization_msgs::MarkerArray markers;
468 
469  pcl::PointCloud<PointType>::Ptr pc_particle_beam(new pcl::PointCloud<PointType>);
470  *pc_particle_beam = *pc_locals["beam"];
471  e.transform(*pc_particle_beam);
472  const auto beam_model = std::dynamic_pointer_cast<LidarMeasurementModelBeam>(lidar_measurements_["beam"]);
473  for (auto& p : pc_particle_beam->points)
474  {
475  const int beam_header_id = p.label;
476  const Vec3 pos = e.pos_ + e.rot_ * origins[beam_header_id];
477  const Vec3 end(p.x, p.y, p.z);
479  const LidarMeasurementModelBeam::BeamStatus beam_status = beam_model->getBeamStatus(kdtree_, pos, end, point);
480 
482  {
483  visualization_msgs::Marker marker;
484  marker.header.frame_id = params_.frame_ids_["map"];
485  marker.header.stamp = header.stamp;
486  marker.ns = "Ray collisions";
487  marker.id = markers.markers.size();
488  marker.type = visualization_msgs::Marker::CUBE;
489  marker.action = 0;
490  marker.pose.position.x = point.pos_.x_;
491  marker.pose.position.y = point.pos_.y_;
492  marker.pose.position.z = point.pos_.z_;
493  marker.pose.orientation.x = 0.0;
494  marker.pose.orientation.y = 0.0;
495  marker.pose.orientation.z = 0.0;
496  marker.pose.orientation.w = 1.0;
497  marker.scale.x = marker.scale.y = marker.scale.z = 0.2;
498  marker.lifetime = ros::Duration(0.2);
499  marker.frame_locked = true;
500  switch (beam_status)
501  {
503  marker.color.a = 0.8;
504  marker.color.r = 0.0;
505  marker.color.g = 1.0;
506  marker.color.b = 0.0;
507  break;
509  marker.color.a = 0.8;
510  marker.color.r = 1.0;
511  marker.color.g = 0.0;
512  marker.color.b = 0.0;
513  break;
515  marker.color.a = 0.2;
516  marker.color.r = 0.0;
517  marker.color.g = 1.0;
518  marker.color.b = 0.0;
519  break;
520  default:
521  break;
522  }
523  markers.markers.push_back(marker);
524  }
525 
526  visualization_msgs::Marker marker;
527  marker.header.frame_id = params_.frame_ids_["map"];
528  marker.header.stamp = header.stamp;
529  marker.ns = "Rays";
530  marker.id = markers.markers.size();
531  marker.type = visualization_msgs::Marker::LINE_STRIP;
532  marker.action = 0;
533  marker.pose.position.x = 0.0;
534  marker.pose.position.y = 0.0;
535  marker.pose.position.z = 0.0;
536  marker.pose.orientation.x = 0.0;
537  marker.pose.orientation.y = 0.0;
538  marker.pose.orientation.z = 0.0;
539  marker.pose.orientation.w = 1.0;
540  marker.scale.x = marker.scale.y = marker.scale.z = 0.04;
541  marker.lifetime = ros::Duration(0.2);
542  marker.frame_locked = true;
543  marker.points.resize(2);
544  marker.points[0].x = pos.x_;
545  marker.points[0].y = pos.y_;
546  marker.points[0].z = pos.z_;
547  marker.points[1].x = end.x_;
548  marker.points[1].y = end.y_;
549  marker.points[1].z = end.z_;
550  marker.colors.resize(2);
551 
552  switch (beam_status)
553  {
555  marker.colors[0].a = 0.5;
556  marker.colors[0].r = 0.0;
557  marker.colors[0].g = 1.0;
558  marker.colors[0].b = 0.0;
559  marker.colors[1].a = 0.8;
560  marker.colors[1].r = 0.0;
561  marker.colors[1].g = 1.0;
562  marker.colors[1].b = 0.0;
563  break;
565  marker.colors[0].a = 0.5;
566  marker.colors[0].r = 1.0;
567  marker.colors[0].g = 0.0;
568  marker.colors[0].b = 0.0;
569  marker.colors[1].a = 0.8;
570  marker.colors[1].r = 1.0;
571  marker.colors[1].g = 0.0;
572  marker.colors[1].b = 0.0;
573  break;
575  marker.colors[0].a = 0.5;
576  marker.colors[0].r = 0.0;
577  marker.colors[0].g = 0.0;
578  marker.colors[0].b = 1.0;
579  marker.colors[1].a = 0.8;
580  marker.colors[1].r = 0.0;
581  marker.colors[1].g = 0.0;
582  marker.colors[1].b = 1.0;
583  break;
585  marker.colors[0].a = 0.2;
586  marker.colors[0].r = 0.0;
587  marker.colors[0].g = 1.0;
588  marker.colors[0].b = 0.0;
589  marker.colors[1].a = 0.2;
590  marker.colors[1].r = 0.0;
591  marker.colors[1].g = 1.0;
592  marker.colors[1].b = 0.0;
593  break;
594  }
595  markers.markers.push_back(marker);
596  }
597 
598  pcl::PointCloud<PointType>::Ptr pc_particle(new pcl::PointCloud<PointType>);
599  *pc_particle = *pc_locals["likelihood"];
600  e.transform(*pc_particle);
601  for (auto& p : pc_particle->points)
602  {
603  visualization_msgs::Marker marker;
604  marker.header.frame_id = params_.frame_ids_["map"];
605  marker.header.stamp = header.stamp;
606  marker.ns = "Sample points";
607  marker.id = markers.markers.size();
608  marker.type = visualization_msgs::Marker::SPHERE;
609  marker.action = 0;
610  marker.pose.position.x = p.x;
611  marker.pose.position.y = p.y;
612  marker.pose.position.z = p.z;
613  marker.pose.orientation.x = 0.0;
614  marker.pose.orientation.y = 0.0;
615  marker.pose.orientation.z = 0.0;
616  marker.pose.orientation.w = 1.0;
617  marker.scale.x = marker.scale.y = marker.scale.z = 0.2;
618  marker.lifetime = ros::Duration(0.2);
619  marker.frame_locked = true;
620  marker.color.a = 1.0;
621  marker.color.r = 1.0;
622  marker.color.g = 0.0;
623  marker.color.b = 1.0;
624 
625  markers.markers.push_back(marker);
626  }
627 
628  pub_debug_marker_.publish(markers);
629  }
630 
631  Vec3 map_pos;
632  Quat map_rot;
633  map_pos = e.pos_ - e.rot_ * odom_.rot_.inv() * odom_.pos_;
634  map_rot = e.rot_ * odom_.rot_.inv();
635 
636  bool jump = false;
637  if (static_cast<int>(pf_->getParticleSize()) > params_.num_particles_)
638  {
639  jump = true;
640  state_prev_ = e;
641  }
642  else
643  {
644  Vec3 jump_axis;
645  float jump_ang;
646  float jump_dist = (e.pos_ - state_prev_.pos_).norm();
647  (e.rot_.inv() * state_prev_.rot_).getAxisAng(jump_axis, jump_ang);
648  if (jump_dist > params_.jump_dist_ ||
649  fabs(jump_ang) > params_.jump_ang_)
650  {
651  ROS_INFO("Pose jumped pos:%0.3f, ang:%0.3f", jump_dist, jump_ang);
652  jump = true;
653 
654  auto integ_reset_func = [](State6DOF& s)
655  {
656  s.odom_err_integ_lin_ = Vec3();
657  s.odom_err_integ_ang_ = Vec3();
658  };
659  pf_->predict(integ_reset_func);
660  }
661  state_prev_ = e;
662  }
663  geometry_msgs::TransformStamped trans;
664  if (has_odom_)
665  trans.header.stamp = odom_last_ + tf_tolerance_base_ + *params_.tf_tolerance_;
666  else
667  trans.header.stamp = ros::Time::now() + tf_tolerance_base_ + *params_.tf_tolerance_;
668  trans.header.frame_id = params_.frame_ids_["map"];
669  trans.child_frame_id = params_.frame_ids_["odom"];
670  const auto rpy = map_rot.getRPY();
671  if (jump)
672  {
673  f_ang_->set(rpy);
674  f_pos_->set(map_pos);
675  }
676  map_rot.setRPY(f_ang_->in(rpy));
677  map_pos = f_pos_->in(map_pos);
678  trans.transform.translation = tf2::toMsg(tf2::Vector3(map_pos.x_, map_pos.y_, map_pos.z_));
679  trans.transform.rotation = tf2::toMsg(tf2::Quaternion(map_rot.x_, map_rot.y_, map_rot.z_, map_rot.w_));
680 
681  std::vector<geometry_msgs::TransformStamped> transforms;
682  transforms.push_back(trans);
683 
684  e.rot_ = map_rot * odom_.rot_;
685  e.pos_ = map_pos + map_rot * odom_.pos_;
686 
687  assert(std::isfinite(e.pos_.x_));
688  assert(std::isfinite(e.pos_.y_));
689  assert(std::isfinite(e.pos_.z_));
690  assert(std::isfinite(e.rot_.x_));
691  assert(std::isfinite(e.rot_.y_));
692  assert(std::isfinite(e.rot_.z_));
693  assert(std::isfinite(e.rot_.w_));
694 
695  trans.header.frame_id = params_.frame_ids_["map"];
696  trans.child_frame_id = params_.frame_ids_["floor"];
697  trans.transform.translation = tf2::toMsg(tf2::Vector3(0.0, 0.0, e.pos_.z_));
698  trans.transform.rotation = tf2::toMsg(tf2::Quaternion(0.0, 0.0, 0.0, 1.0));
699 
700  transforms.push_back(trans);
701 
702  if (params_.publish_tf_)
703  tfb_.sendTransform(transforms);
704 
705  // Calculate covariance from sampled particles to reduce calculation cost on global localization.
706  // Use the number of original particles or at least 10% of full particles.
707  auto cov = pf_->covariance(
708  1.0,
709  std::max(
710  0.1f, static_cast<float>(params_.num_particles_) / pf_->getParticleSize()));
711 
712  geometry_msgs::PoseWithCovarianceStamped pose;
713  pose.header.stamp = header.stamp;
714  pose.header.frame_id = trans.header.frame_id;
715  pose.pose.pose.position.x = e.pos_.x_;
716  pose.pose.pose.position.y = e.pos_.y_;
717  pose.pose.pose.position.z = e.pos_.z_;
718  pose.pose.pose.orientation.x = e.rot_.x_;
719  pose.pose.pose.orientation.y = e.rot_.y_;
720  pose.pose.pose.orientation.z = e.rot_.z_;
721  pose.pose.pose.orientation.w = e.rot_.w_;
722  for (size_t i = 0; i < 36; i++)
723  {
724  pose.pose.covariance[i] = cov[i / 6][i % 6];
725  }
726  pub_pose_.publish(pose);
727 
729  {
730  if (std::sqrt(cov[0][0] + cov[1][1]) > params_.std_warn_thresh_[0] ||
731  std::sqrt(cov[2][2]) > params_.std_warn_thresh_[1] ||
732  std::sqrt(cov[5][5]) > params_.std_warn_thresh_[2])
733  {
734  status_.convergence_status = mcl_3dl_msgs::Status::CONVERGENCE_STATUS_LARGE_STD_VALUE;
735  }
736  }
737 
738  if (status_.convergence_status != mcl_3dl_msgs::Status::CONVERGENCE_STATUS_LARGE_STD_VALUE)
739  {
740  Vec3 fix_axis;
741  const float fix_ang = std::sqrt(cov[3][3] + cov[4][4] + cov[5][5]);
742  const float fix_dist = std::sqrt(cov[0][0] + cov[1][1] + cov[2][2]);
743  ROS_DEBUG("cov: lin %0.3f ang %0.3f", fix_dist, fix_ang);
744  if (fix_dist < params_.fix_dist_ &&
745  fabs(fix_ang) < params_.fix_ang_)
746  {
747  ROS_DEBUG("Localization fixed");
748  status_.convergence_status = mcl_3dl_msgs::Status::CONVERGENCE_STATUS_CONVERGED;
749  }
750  }
751 
752  if (params_.output_pcd_)
753  {
754  pcl::PointCloud<PointType>::Ptr pc_particle(new pcl::PointCloud<PointType>);
755  *pc_particle = *pc_locals["likelihood"];
756  e.transform(*pc_particle);
757  *pc_all_accum_ += *pc_particle;
758  }
759 
760  if ((header.stamp > match_output_last_ + *params_.match_output_interval_ ||
761  header.stamp + ros::Duration(1.0) < match_output_last_) &&
763  {
764  match_output_last_ = header.stamp;
765 
766  pcl::PointCloud<pcl::PointXYZ>::Ptr pc_match(new pcl::PointCloud<pcl::PointXYZ>);
767  pcl::PointCloud<pcl::PointXYZ>::Ptr pc_unmatch(new pcl::PointCloud<pcl::PointXYZ>);
768 
769  pcl::PointCloud<PointType>::Ptr pc_local(new pcl::PointCloud<PointType>);
770  *pc_local = *pc_local_full;
771 
772  e.transform(*pc_local);
773 
774  std::vector<int> id(1);
775  std::vector<float> sqdist(1);
776  const double match_dist_sq = params_.match_output_dist_ * params_.match_output_dist_;
777  for (auto& p : pc_local->points)
778  {
779  if (!kdtree_->radiusSearch(p, params_.unmatch_output_dist_, id, sqdist, 1))
780  {
781  pc_unmatch->points.emplace_back(p.x, p.y, p.z);
782  }
783  else if (sqdist[0] < match_dist_sq)
784  {
785  pc_match->points.emplace_back(p.x, p.y, p.z);
786  }
787  }
789  {
790  sensor_msgs::PointCloud2 pc2;
791  pcl::toROSMsg(*pc_match, pc2);
792  pc2.header.stamp = header.stamp;
793  pc2.header.frame_id = params_.frame_ids_["map"];
794  pub_matched_.publish(pc2);
795  }
797  {
798  sensor_msgs::PointCloud2 pc2;
799  pcl::toROSMsg(*pc_unmatch, pc2);
800  pc2.header.stamp = header.stamp;
801  pc2.header.frame_id = params_.frame_ids_["map"];
802  pub_unmatched_.publish(pc2);
803  }
804  }
805 
807 
808  pf_->resample(State6DOF(
815 
816  std::normal_distribution<float> noise(0.0, 1.0);
817  auto update_noise_func = [this, &noise](State6DOF& s)
818  {
819  s.noise_ll_ = noise(engine_) * params_.odom_err_lin_lin_;
820  s.noise_la_ = noise(engine_) * params_.odom_err_lin_ang_;
821  s.noise_aa_ = noise(engine_) * params_.odom_err_ang_ang_;
822  s.noise_al_ = noise(engine_) * params_.odom_err_ang_lin_;
823  };
824  pf_->predict(update_noise_func);
825 
826  const auto tnow = boost::chrono::high_resolution_clock::now();
827  ROS_DEBUG("MCL (%0.3f sec.)",
828  boost::chrono::duration<float>(tnow - ts).count());
829  const auto err_integ_map = e_max.rot_ * e_max.odom_err_integ_lin_;
830  ROS_DEBUG("odom error integral lin: %0.3f, %0.3f, %0.3f, "
831  "ang: %0.3f, %0.3f, %0.3f, "
832  "pos: %0.3f, %0.3f, %0.3f, "
833  "err on map: %0.3f, %0.3f, %0.3f",
834  e_max.odom_err_integ_lin_.x_,
835  e_max.odom_err_integ_lin_.y_,
836  e_max.odom_err_integ_lin_.z_,
837  e_max.odom_err_integ_ang_.x_,
838  e_max.odom_err_integ_ang_.y_,
839  e_max.odom_err_integ_ang_.z_,
840  e_max.pos_.x_,
841  e_max.pos_.y_,
842  e_max.pos_.z_,
843  err_integ_map.x_,
844  err_integ_map.y_,
845  err_integ_map.z_);
846  ROS_DEBUG("match ratio min: %0.3f, max: %0.3f, pos: %0.3f, %0.3f, %0.3f",
847  match_ratio_min,
848  match_ratio_max,
849  e.pos_.x_,
850  e.pos_.y_,
851  e.pos_.z_);
852  if (match_ratio_max < params_.match_ratio_thresh_)
853  {
854  ROS_WARN_THROTTLE(3.0, "Low match_ratio. Expansion resetting.");
855  pf_->noise(State6DOF(
862  status_.status = mcl_3dl_msgs::Status::EXPANSION_RESETTING;
863  }
864 
865  ros::Time localized_current = ros::Time::now();
866  float dt = (localized_current - localized_last_).toSec();
867  if (dt > 1.0)
868  dt = 1.0;
869  else if (dt < 0.0)
870  dt = 0.0;
872  localized_last_ = localized_current;
873 
874  if (static_cast<int>(pf_->getParticleSize()) > params_.num_particles_)
875  {
876  const int reduced = pf_->getParticleSize() * 0.75;
877  if (reduced > params_.num_particles_)
878  {
879  pf_->resizeParticle(reduced);
880  }
881  else
882  {
883  pf_->resizeParticle(params_.num_particles_);
884  }
885  // wait 99.7% fix (three-sigma)
886  global_localization_fix_cnt_ = 1 + std::ceil(params_.lpf_step_) * 3.0;
887  }
889  {
891  status_.status = mcl_3dl_msgs::Status::GLOBAL_LOCALIZATION;
892  }
893 
894  status_.match_ratio = match_ratio_max;
895  status_.particle_size = pf_->getParticleSize();
897  }
898  void cbLandmark(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
899  {
901  Eigen::Matrix<double, 6, 6>(
902  msg->pose.covariance.data())
903  .cast<float>());
904  const State6DOF measured(
905  Vec3(msg->pose.pose.position.x,
906  msg->pose.pose.position.y,
907  msg->pose.pose.position.z),
908  Quat(msg->pose.pose.orientation.x,
909  msg->pose.pose.orientation.y,
910  msg->pose.pose.orientation.z,
911  msg->pose.pose.orientation.w));
912  auto measure_func = [this, &measured, &nd](const State6DOF& s) -> float
913  {
914  State6DOF diff = s - measured;
915  const Vec3 rot_rpy = diff.rot_.getRPY();
916  const Eigen::Matrix<float, 6, 1> diff_vec =
917  (Eigen::MatrixXf(6, 1) << diff.pos_.x_,
918  diff.pos_.y_,
919  diff.pos_.z_,
920  rot_rpy.x_,
921  rot_rpy.y_,
922  rot_rpy.z_)
923  .finished();
924 
925  const auto n = nd(diff_vec);
926  return n;
927  };
928  pf_->measure(measure_func);
929 
930  pf_->resample(State6DOF(
937 
939  }
940  void cbImu(const sensor_msgs::Imu::ConstPtr& msg)
941  {
942  const Vec3 acc = f_acc_->in(Vec3(
943  msg->linear_acceleration.x,
944  msg->linear_acceleration.y,
945  msg->linear_acceleration.z));
946 
947  if (!has_imu_)
948  {
949  f_acc_->set(Vec3());
950  imu_last_ = msg->header.stamp;
951  has_imu_ = true;
952  return;
953  }
954 
955  float dt = (msg->header.stamp - imu_last_).toSec();
956  if (dt < 0.0 || dt > 5.0)
957  {
958  ROS_WARN("Detected time jump in imu. Resetting.");
959  has_imu_ = false;
960  return;
961  }
962  else if (dt > 0.05)
963  {
964  Vec3 acc_measure = acc.normalized();
965  try
966  {
967  geometry_msgs::Vector3 in, out;
968  in.x = acc_measure.x_;
969  in.y = acc_measure.y_;
970  in.z = acc_measure.z_;
971  // assuming imu frame is regit on base_link
972  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
973  params_.frame_ids_["base_link"], msg->header.frame_id, ros::Time(0));
974  tf2::doTransform(in, out, trans);
975  acc_measure = Vec3(out.x, out.y, out.z);
976 
977  imu_quat_.x_ = msg->orientation.x;
978  imu_quat_.y_ = msg->orientation.y;
979  imu_quat_.z_ = msg->orientation.z;
980  imu_quat_.w_ = msg->orientation.w;
981  Vec3 axis;
982  float angle;
983  imu_quat_.getAxisAng(axis, angle);
984  axis = Quat(trans.transform.rotation.x,
985  trans.transform.rotation.y,
986  trans.transform.rotation.z,
987  trans.transform.rotation.w) *
988  axis;
989  imu_quat_.setAxisAng(axis, angle);
990  }
991  catch (tf2::TransformException& e)
992  {
993  return;
994  }
995 
996  imu_measurement_model_->setAccMeasure(acc_measure);
997  auto imu_measure_func = [this](const State6DOF& s) -> float
998  {
999  return imu_measurement_model_->measure(s);
1000  };
1001  pf_->measure(imu_measure_func);
1002 
1003  imu_last_ = msg->header.stamp;
1004 
1005  if (params_.fake_odom_)
1006  {
1007  nav_msgs::Odometry::Ptr odom(new nav_msgs::Odometry);
1008  odom->header.frame_id = params_.frame_ids_["base_link"];
1009  odom->header.stamp = msg->header.stamp;
1010  odom->pose.pose.orientation.x = imu_quat_.x_;
1011  odom->pose.pose.orientation.y = imu_quat_.y_;
1012  odom->pose.pose.orientation.z = imu_quat_.z_;
1013  odom->pose.pose.orientation.w = imu_quat_.w_;
1014  cbOdom(odom);
1015  }
1016  }
1017  }
1018  bool cbResizeParticle(mcl_3dl_msgs::ResizeParticleRequest& request,
1019  mcl_3dl_msgs::ResizeParticleResponse& response)
1020  {
1021  pf_->resizeParticle(request.size);
1022  publishParticles();
1023  return true;
1024  }
1025  bool cbExpansionReset(std_srvs::TriggerRequest& request,
1026  std_srvs::TriggerResponse& response)
1027  {
1028  pf_->noise(State6DOF(
1035  publishParticles();
1036  return true;
1037  }
1038  bool cbGlobalLocalization(std_srvs::TriggerRequest& request,
1039  std_srvs::TriggerResponse& response)
1040  {
1041  if (!has_map_)
1042  {
1043  response.success = false;
1044  response.message = "No map received.";
1045  return true;
1046  }
1047  pcl::PointCloud<PointType>::Ptr points(new pcl::PointCloud<PointType>);
1048 
1049  pcl::VoxelGrid<PointType> ds;
1050  ds.setInputCloud(pc_map_);
1051  ds.setLeafSize(
1055  ds.filter(*points);
1056 
1057  pcl::KdTreeFLANN<PointType>::Ptr kdtree(new pcl::KdTreeFLANN<PointType>);
1058  kdtree->setPointRepresentation(point_rep_);
1059  kdtree->setInputCloud(points);
1060 
1061  auto pc_filter = [this, kdtree](const PointType& p)
1062  {
1063  std::vector<int> id(1);
1064  std::vector<float> sqdist(1);
1065  auto p2 = p;
1066  p2.z += 0.01 + params_.global_localization_grid_;
1067 
1068  return kdtree->radiusSearch(
1069  p2, params_.global_localization_grid_, id, sqdist, 1);
1070  };
1071  points->erase(
1072  std::remove_if(points->begin(), points->end(), pc_filter),
1073  points->end());
1074 
1075  const int dir = params_.global_localization_div_yaw_;
1076  pf_->resizeParticle(points->size() * dir);
1077  auto pit = points->begin();
1078 
1079  const float prob = 1.0 / static_cast<float>(points->size());
1080  int cnt = 0;
1081  for (auto& particle : *pf_)
1082  {
1083  assert(pit != points->end());
1084  particle.probability_ = prob;
1085  particle.probability_bias_ = 1.0;
1086  particle.state_ = State6DOF(
1087  Vec3(pit->x, pit->y, pit->z),
1088  (Quat(Vec3(0.0, 0.0, 2.0 * M_PI * cnt / dir)) * imu_quat_).normalized());
1089  if (++cnt >= dir)
1090  {
1091  cnt = 0;
1092  ++pit;
1093  }
1094  }
1095  response.success = true;
1096  response.message = std::to_string(pf_->getParticleSize()) + " particles";
1097  return true;
1098  }
1099 
1101  {
1102  geometry_msgs::PoseArray pa;
1103  if (has_odom_)
1104  pa.header.stamp = odom_last_ + tf_tolerance_base_ + *params_.tf_tolerance_;
1105  else
1106  pa.header.stamp = ros::Time::now() + tf_tolerance_base_ + *params_.tf_tolerance_;
1107  pa.header.frame_id = params_.frame_ids_["map"];
1108  for (size_t i = 0; i < pf_->getParticleSize(); i++)
1109  {
1110  geometry_msgs::Pose pm;
1111  auto p = pf_->getParticle(i);
1112  p.rot_.normalize();
1113  pm.position.x = p.pos_.x_;
1114  pm.position.y = p.pos_.y_;
1115  pm.position.z = p.pos_.z_;
1116  pm.orientation.x = p.rot_.x_;
1117  pm.orientation.y = p.rot_.y_;
1118  pm.orientation.z = p.rot_.z_;
1119  pm.orientation.w = p.rot_.w_;
1120  pa.poses.push_back(pm);
1121  }
1122  pub_particle_.publish(pa);
1123  }
1124 
1125  float getEntropy()
1126  {
1127  float sum = 0.0f;
1128  for (auto& particle : *pf_)
1129  {
1130  sum += particle.probability_;
1131  }
1132 
1133  float entropy = 0.0f;
1134  for (auto& particle : *pf_)
1135  {
1136  if (particle.probability_ / sum > 0.0)
1137  entropy += particle.probability_ / sum * std::log(particle.probability_ / sum);
1138  }
1139 
1140  return -entropy;
1141  }
1142 
1144  {
1145  if (status_.error == mcl_3dl_msgs::Status::ERROR_POINTS_NOT_FOUND)
1146  {
1147  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Valid points does not found.");
1148  }
1149  else if (status_.convergence_status == mcl_3dl_msgs::Status::CONVERGENCE_STATUS_LARGE_STD_VALUE)
1150  {
1151  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Too Large Standard Deviation.");
1152  }
1153  else
1154  {
1155  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "OK");
1156  }
1157 
1158  stat.add("Map Availability", has_map_ ? "true" : "false");
1159  stat.add("Odometry Availability", has_odom_ ? "true" : "false");
1160  stat.add("IMU Availability", has_imu_ ? "true" : "false");
1161 
1162  status_.entropy = getEntropy();
1164  }
1165 
1166  void loadMapCloud(const pcl::PointCloud<PointType>::Ptr& map_cloud)
1167  {
1168  pc_map_.reset(new pcl::PointCloud<PointType>);
1169  pc_map2_.reset();
1170  pc_update_.reset();
1171  pcl::VoxelGrid<PointType> ds;
1172  ds.setInputCloud(map_cloud);
1174  ds.filter(*pc_map_);
1175  pc_all_accum_.reset(new pcl::PointCloud<PointType>);
1176  has_map_ = true;
1177 
1178  accumClear();
1179  accum_->reset();
1180 
1181  ROS_INFO("map original: %d points", static_cast<int>(map_cloud->points.size()));
1182  ROS_INFO("map reduced: %d points", static_cast<int>(pc_map_->points.size()));
1183 
1184  // output map for visualization purposes:
1186  }
1187 
1188  bool cbLoadPCD(mcl_3dl_msgs::LoadPCD::Request& req, mcl_3dl_msgs::LoadPCD::Response& resp)
1189  {
1190  ROS_INFO("map received");
1191 
1192  pcl::PointCloud<PointType>::Ptr pc_tmp(new pcl::PointCloud<PointType>);
1193  if (pcl::io::loadPCDFile<PointType>(req.pcd_path, *pc_tmp) == -1)
1194  {
1195  ROS_ERROR_STREAM("Couldn't read file " << req.pcd_path);
1196  has_map_ = false;
1197  resp.success = false;
1198  return true;
1199  }
1200 
1201  pcl_conversions::toPCL(ros::Time::now(), pc_tmp->header.stamp);
1202  pc_tmp->header.frame_id = params_.frame_ids_["map"];
1203 
1204  loadMapCloud(pc_tmp);
1205 
1206  resp.success = true;
1207  return true;
1208  }
1209 
1210 public:
1212  : pnh_("~")
1213  , tfl_(tfbuf_)
1214  , cnt_measure_(0)
1217  , engine_(seed_gen_())
1218  {
1219  }
1220  bool configure()
1221  {
1223 
1224  if (!params_.load(pnh_))
1225  {
1226  ROS_ERROR("Failed to load parameters");
1227  return false;
1228  }
1229 
1230  if (!params_.fake_odom_)
1231  {
1232  int odom_queue_size;
1233  pnh_.param("odom_queue_size", odom_queue_size, 200);
1235  nh_, "odom",
1236  pnh_, "odom", odom_queue_size, &MCL3dlNode::cbOdom, this);
1237  }
1238  if (!params_.fake_imu_)
1239  {
1240  int imu_queue_size;
1241  pnh_.param("imu_queue_size", imu_queue_size, 200);
1243  nh_, "imu/data",
1244  pnh_, "imu", imu_queue_size, &MCL3dlNode::cbImu, this);
1245  }
1246 
1247  int cloud_queue_size;
1248  pnh_.param("cloud_queue_size", cloud_queue_size, 100);
1250  nh_, "cloud",
1251  pnh_, "cloud", cloud_queue_size, &MCL3dlNode::cbCloud, this);
1253  nh_, "mapcloud",
1254  pnh_, "mapcloud", 1, &MCL3dlNode::cbMapcloud, this);
1256  nh_, "mapcloud_update",
1257  pnh_, "mapcloud_update", 1, &MCL3dlNode::cbMapcloudUpdate, this);
1259  nh_, "initialpose",
1260  pnh_, "initialpose", 1, &MCL3dlNode::cbPosition, this);
1262  nh_, "mcl_measurement",
1263  pnh_, "landmark", 1, &MCL3dlNode::cbLandmark, this);
1264 
1265  pub_pose_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose", 5, false);
1266  pub_particle_ = pnh_.advertise<geometry_msgs::PoseArray>("particles", 1, true);
1267  pub_mapcloud_ = pnh_.advertise<sensor_msgs::PointCloud2>("updated_map", 1, true);
1268  pub_debug_marker_ = pnh_.advertise<visualization_msgs::MarkerArray>("debug_marker", 1, true);
1269  pub_status_ = pnh_.advertise<mcl_3dl_msgs::Status>("status", 1, true);
1270  pub_matched_ = pnh_.advertise<sensor_msgs::PointCloud2>("matched", 2, true);
1271  pub_unmatched_ = pnh_.advertise<sensor_msgs::PointCloud2>("unmatched", 2, true);
1272 
1274  nh_, "resize_mcl_particle",
1275  pnh_, "resize_particle", &MCL3dlNode::cbResizeParticle, this);
1277  nh_, "global_localization",
1278  pnh_, "global_localization", &MCL3dlNode::cbGlobalLocalization, this);
1280  nh_, "expansion_resetting",
1281  pnh_, "expansion_resetting", &MCL3dlNode::cbExpansionReset, this);
1283 
1284  point_rep_->setRescaleValues(params_.dist_weight_.data());
1285 
1286  pf_.reset(new pf::ParticleFilter<State6DOF,
1287  float,
1289  std::default_random_engine>(params_.num_particles_));
1291 
1292  f_pos_.reset(new FilterVec3(
1295  Vec3()));
1296  f_ang_.reset(new FilterVec3(
1299  Vec3(), true));
1300  f_acc_.reset(new FilterVec3(
1303  Vec3()));
1304 
1305  if (params_.accum_cloud_ == 0)
1307  else
1308  accum_.reset(
1310 
1311  imu_quat_ = Quat(0.0, 0.0, 0.0, 1.0);
1312 
1313  has_odom_ = has_map_ = has_imu_ = false;
1314  localize_rate_.reset(new Filter(Filter::FILTER_LPF, 5.0, 0.0));
1315 
1316  lidar_measurements_["likelihood"] =
1319  lidar_measurements_["beam"] =
1327 
1328  float max_search_radius = 0;
1329  for (auto& lm : lidar_measurements_)
1330  {
1331  lm.second->loadConfig(pnh_, lm.first);
1332  max_search_radius = std::max(max_search_radius, lm.second->getMaxSearchRange());
1333 
1335  {
1336  auto sampler = std::make_shared<PointCloudSamplerWithNormal<PointType>>();
1337  sampler->loadConfig(pnh_);
1338  lm.second->setRandomSampler(sampler);
1339  }
1340  else
1341  {
1342  auto sampler = std::make_shared<PointCloudUniformSampler<PointType>>();
1343  lm.second->setRandomSampler(sampler);
1344  }
1345  }
1346 
1347  ROS_DEBUG("max_search_radius: %0.3f", max_search_radius);
1348  kdtree_.reset(new ChunkedKdtree<PointType>(params_.map_chunk_, max_search_radius));
1349  kdtree_->setEpsilon(params_.map_grid_min_ / 16);
1350  kdtree_->setPointRepresentation(point_rep_);
1351 
1355 
1356  diag_updater_.setHardwareID("none");
1357  diag_updater_.add("Status", this, &MCL3dlNode::diagnoseStatus);
1358 
1359  return true;
1360  }
1362  {
1364  {
1365  std::cerr << "mcl_3dl: saving pcd file.";
1366  std::cerr << " (" << pc_all_accum_->points.size() << " points)" << std::endl;
1367  pcl::io::savePCDFileBinary("mcl_3dl.pcd", *pc_all_accum_);
1368  }
1369  }
1370 
1372  {
1373  if (has_map_)
1374  {
1375  const auto ts = boost::chrono::high_resolution_clock::now();
1376  if (pc_update_)
1377  {
1378  if (!pc_map2_)
1379  pc_map2_.reset(new pcl::PointCloud<PointType>);
1380  *pc_map2_ = *pc_map_ + *pc_update_;
1381  pc_update_.reset();
1383  }
1384  else
1385  {
1386  if (pc_map2_)
1387  return;
1388  pc_map2_ = pc_map_;
1389  }
1390  kdtree_->setInputCloud(pc_map2_);
1391 
1392  sensor_msgs::PointCloud2 out;
1393  pcl::toROSMsg(*pc_map2_, out);
1394  pub_mapcloud_.publish(out);
1395  const auto tnow = boost::chrono::high_resolution_clock::now();
1396  ROS_DEBUG("Map update (%0.3f sec.)",
1397  boost::chrono::duration<float>(tnow - ts).count());
1398  }
1399  }
1400 
1401 protected:
1404 
1424 
1428 
1429  std::shared_ptr<FilterVec3> f_pos_;
1430  std::shared_ptr<FilterVec3> f_ang_;
1431  std::shared_ptr<FilterVec3> f_acc_;
1432  std::shared_ptr<Filter> localize_rate_;
1435 
1437 
1440  bool has_map_;
1442  bool has_imu_;
1451  mcl_3dl_msgs::Status status_;
1452 
1453  MyPointRepresentation::Ptr point_rep_;
1454 
1455  pcl::PointCloud<PointType>::Ptr pc_map_;
1456  pcl::PointCloud<PointType>::Ptr pc_map2_;
1457  pcl::PointCloud<PointType>::Ptr pc_update_;
1458  pcl::PointCloud<PointType>::Ptr pc_all_accum_;
1460 
1462  pcl::PointCloud<PointType>::Ptr pc_local_accum_;
1463  std::vector<std_msgs::Header> pc_accum_header_;
1464 
1465  std::map<
1466  std::string,
1471 
1472  std::random_device seed_gen_;
1473  std::default_random_engine engine_;
1474 };
1475 } // namespace mcl_3dl
1476 
1477 int main(int argc, char* argv[])
1478 {
1479  ros::init(argc, argv, "mcl_3dl");
1480 
1481  mcl_3dl::MCL3dlNode mcl;
1482  if (!mcl.configure())
1483  {
1484  return 1;
1485  }
1486  ros::spin();
1487 
1488  return 0;
1489 }
float z_
Definition: vec3.h:42
std::default_random_engine engine_
Definition: mcl_3dl.cpp:1473
ros::Time match_output_last_
Definition: mcl_3dl.cpp:1438
void setAxisAng(const Vec3 &axis, const float &ang)
Definition: quat.h:216
ros::NodeHandle pnh_
Definition: mcl_3dl.cpp:1403
ros::NodeHandle nh_
Definition: mcl_3dl.cpp:1402
State6DOF state_prev_
Definition: mcl_3dl.cpp:1445
std::shared_ptr< pf::ParticleFilter< State6DOF, float, ParticleWeightedMeanQuat, std::default_random_engine > > pf_
Definition: mcl_3dl.cpp:107
bool load(ros::NodeHandle &nh)
Definition: parameters.cpp:43
double update_downsample_x_
Definition: parameters.h:53
void cbOdom(const nav_msgs::Odometry::ConstPtr &msg)
Definition: mcl_3dl.cpp:200
double expansion_var_z_
Definition: parameters.h:71
double resample_var_roll_
Definition: parameters.h:66
f
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void summary(unsigned char lvl, const std::string s)
double odom_err_lin_ang_
Definition: parameters.h:81
float y_
Definition: quat.h:44
MyPointRepresentation::Ptr point_rep_
Definition: mcl_3dl.cpp:1453
ros::Publisher pub_debug_marker_
Definition: mcl_3dl.cpp:1417
double unmatch_output_dist_
Definition: parameters.h:90
void setHardwareID(const std::string &hwid)
ros::Subscriber sub_mapcloud_
Definition: mcl_3dl.cpp:1406
XmlRpcServer s
std::shared_ptr< ChunkedKdtree > Ptr
mcl_3dl::Vec3 pos_
Definition: state_6dof.h:52
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
double match_output_dist_
Definition: parameters.h:89
void add(const std::string &name, TaskFunction f)
std::random_device seed_gen_
Definition: mcl_3dl.cpp:1472
bool cbLoadPCD(mcl_3dl_msgs::LoadPCD::Request &req, mcl_3dl_msgs::LoadPCD::Response &resp)
Definition: mcl_3dl.cpp:1188
double update_downsample_z_
Definition: parameters.h:55
tf2_ros::TransformBroadcaster tfb_
Definition: mcl_3dl.cpp:1427
double expansion_var_roll_
Definition: parameters.h:72
ros::ServiceServer srv_global_localization_
Definition: mcl_3dl.cpp:1421
ros::Subscriber sub_cloud_
Definition: mcl_3dl.cpp:1405
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
virtual void copyToFloatArray(const PointType &p, float *out) const
Definition: mcl_3dl.cpp:120
#define ROS_WARN(...)
ros::Subscriber sub_odom_
Definition: mcl_3dl.cpp:1408
void loadMapCloud(const pcl::PointCloud< PointType >::Ptr &map_cloud)
Definition: mcl_3dl.cpp:1166
double map_downsample_x_
Definition: parameters.h:50
ros::Publisher pub_status_
Definition: mcl_3dl.cpp:1418
pcl::PointCloud< PointType >::Ptr pc_update_
Definition: mcl_3dl.cpp:1457
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::shared_ptr< FilterVec3 > f_ang_
Definition: mcl_3dl.cpp:1430
std::map< std::string, LidarMeasurementModelBase::Ptr > lidar_measurements_
Definition: mcl_3dl.cpp:1468
ChunkedKdtree< PointType >::Ptr kdtree_
Definition: mcl_3dl.cpp:1459
pcl::PointCloud< PointType >::Ptr pc_map2_
Definition: mcl_3dl.cpp:1456
std::shared_ptr< ros::Duration > map_update_interval_
Definition: parameters.h:84
ros::ServiceServer advertiseService(ros::NodeHandle &nh_new, const std::string &service_new, ros::NodeHandle &nh_old, const std::string &service_old, bool(T::*srv_func)(MReq &, MRes &), T *obj)
tf2_ros::Buffer tfbuf_
Definition: mcl_3dl.cpp:1425
ros::Publisher pub_particle_
Definition: mcl_3dl.cpp:1412
ros::Subscriber sub_mapcloud_update_
Definition: mcl_3dl.cpp:1407
Parameters params_
Definition: mcl_3dl.cpp:1436
std::shared_ptr< Filter > localize_rate_
Definition: mcl_3dl.cpp:1432
bool param(const std::string &param_name, T &param_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 getAxisAng(Vec3 &axis, float &ang) const
Definition: quat.h:226
void publish(const boost::shared_ptr< M > &message) const
double global_localization_grid_
Definition: parameters.h:58
double odom_err_ang_ang_
Definition: parameters.h:83
void cbMapUpdateTimer(const ros::TimerEvent &event)
Definition: mcl_3dl.cpp:1371
constexpr Vec3 getRPY() const
Definition: quat.h:191
double expansion_var_y_
Definition: parameters.h:70
bool accumCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: mcl_3dl.cpp:274
void diagnoseStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: mcl_3dl.cpp:1143
bool fromROSMsg(const sensor_msgs::PointCloud2 &msg, pcl::PointCloud< PointT > &pc)
ros::ServiceServer srv_expansion_reset_
Definition: mcl_3dl.cpp:1422
ros::Time localized_last_
Definition: mcl_3dl.cpp:1433
void cbLandmark(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
Definition: mcl_3dl.cpp:898
State6DOF initial_pose_std_
Definition: parameters.h:109
#define ROS_WARN_THROTTLE(period,...)
double map_downsample_y_
Definition: parameters.h:51
#define ROS_INFO(...)
CloudAccumulationLogicBase::Ptr accum_
Definition: mcl_3dl.cpp:1461
float w_
Definition: quat.h:46
float y_
Definition: vec3.h:41
ros::Publisher pub_unmatched_
Definition: mcl_3dl.cpp:1416
ros::Subscriber sub_landmark_
Definition: mcl_3dl.cpp:1411
MotionPredictionModelBase::Ptr motion_prediction_model_
Definition: mcl_3dl.cpp:1470
ros::Publisher pub_matched_
Definition: mcl_3dl.cpp:1415
std::shared_ptr< LidarMeasurementModelBase > Ptr
std::array< float, 3 > std_warn_thresh_
Definition: parameters.h:107
pcl::PointCloud< PointType >::Ptr pc_local_accum_
Definition: mcl_3dl.cpp:1462
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
bool cbExpansionReset(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
Definition: mcl_3dl.cpp:1025
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double odom_err_integ_lin_tc_
Definition: parameters.h:94
ROSCPP_DECL void spin()
double resample_var_yaw_
Definition: parameters.h:68
tf2_ros::TransformListener tfl_
Definition: mcl_3dl.cpp:1426
double odom_err_lin_lin_
Definition: parameters.h:80
void sendTransform(const geometry_msgs::TransformStamped &transform)
double expansion_var_yaw_
Definition: parameters.h:74
mcl_3dl_msgs::Status status_
Definition: mcl_3dl.cpp:1451
std::shared_ptr< FilterVec3 > f_acc_
Definition: mcl_3dl.cpp:1431
State6DOF odom_prev_
Definition: mcl_3dl.cpp:1444
std::shared_ptr< FilterVec3 > f_pos_
Definition: mcl_3dl.cpp:1429
mcl_3dl::Quat rot_
Definition: state_6dof.h:53
void cbMapcloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: mcl_3dl.cpp:127
B toMsg(const A &a)
double map_downsample_z_
Definition: parameters.h:52
ros::Subscriber sub_imu_
Definition: mcl_3dl.cpp:1409
ImuMeasurementModelBase::Ptr imu_measurement_model_
Definition: mcl_3dl.cpp:1469
double resample_var_z_
Definition: parameters.h:65
double odom_err_ang_lin_
Definition: parameters.h:82
void checkCompatMode()
Definition: compatibility.h:62
std::shared_ptr< ImuMeasurementModelBase > Ptr
int main(int argc, char *argv[])
Definition: mcl_3dl.cpp:1477
float x_
Definition: vec3.h:40
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints())
std::map< std::string, std::string > frame_ids_
Definition: parameters.h:106
double resample_var_y_
Definition: parameters.h:64
void setRPY(const Vec3 &rpy)
Definition: quat.h:202
void setParticleStatistics(const State6DOF &mean, const std::vector< State6DOF > &covariances)
ros::Time odom_last_
Definition: mcl_3dl.cpp:1439
double expansion_var_x_
Definition: parameters.h:69
std::vector< std_msgs::Header > pc_accum_header_
Definition: mcl_3dl.cpp:1463
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
static Time now()
double expansion_var_pitch_
Definition: parameters.h:73
double odom_err_integ_ang_tc_
Definition: parameters.h:96
ros::Publisher pub_mapcloud_
Definition: mcl_3dl.cpp:1413
double match_ratio_thresh_
Definition: parameters.h:75
ros::Timer map_update_timer_
Definition: mcl_3dl.cpp:1419
const std::string header
void cbPosition(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
Definition: mcl_3dl.cpp:155
ros::Time imu_last_
Definition: mcl_3dl.cpp:1446
ros::Duration tf_tolerance_base_
Definition: mcl_3dl.cpp:1434
void cbImu(const sensor_msgs::Imu::ConstPtr &msg)
Definition: mcl_3dl.cpp:940
void add(const std::string &key, const T &val)
ros::ServiceServer srv_load_pcd_
Definition: mcl_3dl.cpp:1423
diagnostic_updater::Updater diag_updater_
Definition: mcl_3dl.cpp:1450
bool use_random_sampler_with_normal_
Definition: parameters.h:110
pcl::PointCloud< PointType >::Ptr pc_map_
Definition: mcl_3dl.cpp:1455
#define ROS_ERROR_STREAM(args)
uint32_t getNumSubscribers() const
std::shared_ptr< ros::Duration > match_output_interval_
Definition: parameters.h:98
bool cbResizeParticle(mcl_3dl_msgs::ResizeParticleRequest &request, mcl_3dl_msgs::ResizeParticleResponse &response)
Definition: mcl_3dl.cpp:1018
#define ROS_ERROR(...)
std::shared_ptr< ros::Duration > tf_tolerance_
Definition: parameters.h:99
ros::Publisher pub_pose_
Definition: mcl_3dl.cpp:1414
double odom_err_integ_lin_sigma_
Definition: parameters.h:95
Vec3 normalized() const
Definition: vec3.h:157
float z_
Definition: quat.h:45
void cbMapcloudUpdate(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: mcl_3dl.cpp:141
State6DOF initial_pose_
Definition: parameters.h:108
double update_downsample_y_
Definition: parameters.h:54
int global_localization_div_yaw_
Definition: parameters.h:59
ros::ServiceServer srv_particle_size_
Definition: mcl_3dl.cpp:1420
std::shared_ptr< CloudAccumulationLogicBase > Ptr
Definition: cloud_accum.h:45
size_t global_localization_fix_cnt_
Definition: mcl_3dl.cpp:1449
constexpr Quat inv() const
Definition: quat.h:187
double odom_err_integ_ang_sigma_
Definition: parameters.h:97
double resample_var_x_
Definition: parameters.h:63
ros::Subscriber sub_position_
Definition: mcl_3dl.cpp:1410
pcl::PointCloud< PointType >::Ptr pc_all_accum_
Definition: mcl_3dl.cpp:1458
float x_
Definition: quat.h:43
bool cbGlobalLocalization(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
Definition: mcl_3dl.cpp:1038
double resample_var_pitch_
Definition: parameters.h:67
#define ROS_DEBUG(...)
std::shared_ptr< MotionPredictionModelBase > Ptr
void cbCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: mcl_3dl.cpp:248
std::array< float, 4 > dist_weight_
Definition: parameters.h:102


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 4 2023 02:11:07