mcl_3dl.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2018, 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 <map>
32 #include <memory>
33 #include <string>
34 #include <utility>
35 #include <vector>
36 
37 #include <boost/chrono.hpp>
38 #include <boost/shared_ptr.hpp>
39 
40 #include <ros/ros.h>
41 #include <sensor_msgs/PointCloud.h>
42 #include <sensor_msgs/PointCloud2.h>
44 #include <nav_msgs/Odometry.h>
45 #include <sensor_msgs/Imu.h>
46 #include <geometry_msgs/PoseArray.h>
47 #include <geometry_msgs/PoseWithCovarianceStamped.h>
48 #include <geometry_msgs/TransformStamped.h>
49 #include <visualization_msgs/MarkerArray.h>
50 #include <mcl_3dl_msgs/ResizeParticle.h>
51 #include <mcl_3dl_msgs/Status.h>
52 #include <std_srvs/Trigger.h>
53 
58 
60 #include <pcl/point_types.h>
61 #include <pcl_ros/point_cloud.h>
62 #include <pcl_ros/transforms.h>
63 #include <pcl/conversions.h>
64 #include <pcl/filters/voxel_grid.h>
65 #include <pcl/kdtree/kdtree.h>
66 #include <pcl/kdtree/kdtree_flann.h>
67 
68 #include <Eigen/Core>
69 
71 
72 #include <mcl_3dl/chunked_kdtree.h>
73 #include <mcl_3dl/filter.h>
81 #include <mcl_3dl/nd.h>
82 #include <mcl_3dl/parameters.h>
83 #include <mcl_3dl/pf.h>
85 #include <mcl_3dl/point_types.h>
86 #include <mcl_3dl/quat.h>
87 #include <mcl_3dl/raycast.h>
88 #include <mcl_3dl/state_6dof.h>
89 #include <mcl_3dl/vec3.h>
90 
92 
93 namespace mcl_3dl
94 {
96 {
97 protected:
99  std::shared_ptr<pf::ParticleFilter<State6DOF, float, ParticleWeightedMeanQuat>> pf_;
100 
101  class MyPointRepresentation : public pcl::PointRepresentation<PointType>
102  {
103  using pcl::PointRepresentation<PointType>::nr_dimensions_;
104 
105  public:
107  {
108  nr_dimensions_ = 3;
109  }
110 
111  virtual void copyToFloatArray(const PointType& p, float* out) const
112  {
113  out[0] = p.x;
114  out[1] = p.y;
115  out[2] = p.z;
116  }
117  };
118  void cbMapcloud(const sensor_msgs::PointCloud2::ConstPtr& msg)
119  {
120  ROS_INFO("map received");
121  pcl::PointCloud<PointType>::Ptr pc_tmp(new pcl::PointCloud<PointType>);
122  if (!mcl_3dl::fromROSMsg(*msg, *pc_tmp))
123  {
124  has_map_ = false;
125  return;
126  }
127 
128  pc_map_.reset(new pcl::PointCloud<PointType>);
129  pc_map2_.reset();
130  pc_update_.reset();
132  ds.setInputCloud(pc_tmp);
134  ds.filter(*pc_map_);
135  pc_local_accum_.reset(new pcl::PointCloud<PointType>);
136  pc_all_accum_.reset(new pcl::PointCloud<PointType>);
137  frame_num_ = 0;
138  has_map_ = true;
139 
140  ROS_INFO("map original: %d points", (int)pc_tmp->points.size());
141  ROS_INFO("map reduced: %d points", (int)pc_map_->points.size());
142 
144  }
145  void cbMapcloudUpdate(const sensor_msgs::PointCloud2::ConstPtr& msg)
146  {
147  ROS_INFO("map_update received");
148  pcl::PointCloud<PointType>::Ptr pc_tmp(new pcl::PointCloud<PointType>);
149  if (!mcl_3dl::fromROSMsg(*msg, *pc_tmp))
150  return;
151 
152  pc_update_.reset(new pcl::PointCloud<PointType>);
154  ds.setInputCloud(pc_tmp);
156  ds.filter(*pc_update_);
157  }
158 
159  void cbPosition(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
160  {
161  geometry_msgs::PoseStamped pose_in, pose;
162  pose_in.header = msg->header;
163  pose_in.pose = msg->pose.pose;
164  try
165  {
166  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
167  frame_ids_["map"], pose_in.header.frame_id, pose_in.header.stamp, ros::Duration(1.0));
168  tf2::doTransform(pose_in, pose, trans);
169  }
170  catch (tf2::TransformException& e)
171  {
172  return;
173  }
174  pf_->init(
175  State6DOF(
176  Vec3(pose.pose.position.x, pose.pose.position.y, pose.pose.position.z),
177  Quat(pose.pose.orientation.x,
178  pose.pose.orientation.y,
179  pose.pose.orientation.z,
180  pose.pose.orientation.w)),
181  State6DOF(
182  Vec3(msg->pose.covariance[0],
183  msg->pose.covariance[6 * 1 + 1],
184  msg->pose.covariance[6 * 2 + 2]),
185  Vec3(msg->pose.covariance[6 * 3 + 3],
186  msg->pose.covariance[6 * 4 + 4],
187  msg->pose.covariance[6 * 5 + 5])));
188  pc_update_.reset();
189  auto integ_reset_func = [](State6DOF& s)
190  {
191  s.odom_err_integ_lin_ = Vec3();
192  s.odom_err_integ_ang_ = Vec3();
193  };
194  pf_->predict(integ_reset_func);
195 
197  }
198 
199  void cbOdom(const nav_msgs::Odometry::ConstPtr& msg)
200  {
201  odom_ =
202  State6DOF(
203  Vec3(msg->pose.pose.position.x,
204  msg->pose.pose.position.y,
205  msg->pose.pose.position.z),
206  Quat(msg->pose.pose.orientation.x,
207  msg->pose.pose.orientation.y,
208  msg->pose.pose.orientation.z,
209  msg->pose.pose.orientation.w));
210  if (!has_odom_)
211  {
212  odom_prev_ = odom_;
213  odom_last_ = msg->header.stamp;
214  has_odom_ = true;
215  return;
216  }
217  const float dt = (msg->header.stamp - odom_last_).toSec();
218  if (dt < 0.0 || dt > 5.0)
219  {
220  ROS_WARN("Detected time jump in odometry. Resetting.");
221  has_odom_ = false;
222  return;
223  }
224  else if (dt > 0.05)
225  {
226  motion_prediction_model_->setOdoms(odom_prev_, odom_, dt);
227  auto prediction_func = [this](State6DOF& s)
228  {
229  motion_prediction_model_->predict(s);
230  };
231  pf_->predict(prediction_func);
232  odom_last_ = msg->header.stamp;
233  odom_prev_ = odom_;
234  }
235  if (fake_imu_)
236  {
237  const Vec3 accel = odom_.rot_ * Vec3(0.0, 0.0, 1.0);
238  sensor_msgs::Imu::Ptr imu(new sensor_msgs::Imu);
239  imu->header = msg->header;
240  imu->linear_acceleration.x = accel.x_;
241  imu->linear_acceleration.y = accel.y_;
242  imu->linear_acceleration.z = accel.z_;
243  imu->orientation = msg->pose.pose.orientation;
244  cbImu(imu);
245  }
246  }
247  void cbCloud(const sensor_msgs::PointCloud2::ConstPtr& msg)
248  {
249  mcl_3dl_msgs::Status status;
250  status.header.stamp = ros::Time::now();
251  status.status = mcl_3dl_msgs::Status::NORMAL;
252 
253  if (!has_map_)
254  return;
255  if (frames_.find(msg->header.frame_id) == frames_.end())
256  {
257  frames_[msg->header.frame_id] = true;
258  frames_v_.push_back(msg->header.frame_id);
259  }
260 
261  sensor_msgs::PointCloud2 pc_bl;
262  try
263  {
264  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
265  frame_ids_["odom"], msg->header.frame_id, msg->header.stamp, ros::Duration(0.1));
266  tf2::doTransform(*msg, pc_bl, trans);
267  }
268  catch (tf2::TransformException& e)
269  {
270  ROS_INFO("Failed to transform pointcloud: %s", e.what());
271  pc_local_accum_.reset(new pcl::PointCloud<PointType>);
272  pc_accum_header_.clear();
273  return;
274  }
275  pcl::PointCloud<PointType>::Ptr pc_tmp(new pcl::PointCloud<PointType>);
276  if (!mcl_3dl::fromROSMsg(pc_bl, *pc_tmp))
277  return;
278 
279  for (auto& p : pc_tmp->points)
280  {
281  p.label = pc_accum_header_.size();
282  }
283  *pc_local_accum_ += *pc_tmp;
284  pc_local_accum_->header.frame_id = frame_ids_["odom"];
285  pc_accum_header_.push_back(msg->header);
286 
287  if (frames_v_[frame_num_].compare(msg->header.frame_id) != 0)
288  return;
289  frame_num_++;
290  if (frame_num_ >= frames_v_.size())
291  frame_num_ = 0;
292 
293  if (frame_num_ != 0)
294  return;
295 
296  cnt_accum_++;
297  if (cnt_accum_ % params_.accum_cloud_ != 0)
298  return;
299 
300  cnt_measure_++;
302  {
303  pc_local_accum_.reset(new pcl::PointCloud<PointType>);
304  pc_accum_header_.clear();
305  return;
306  }
307 
308  try
309  {
310  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
311  frame_ids_["base_link"],
312  pc_local_accum_->header.frame_id,
314 
315  const Eigen::Affine3f trans_eigen =
316  Eigen::Translation3f(
317  trans.transform.translation.x,
318  trans.transform.translation.y,
319  trans.transform.translation.z) *
320  Eigen::Quaternionf(
321  trans.transform.rotation.w,
322  trans.transform.rotation.x,
323  trans.transform.rotation.y,
324  trans.transform.rotation.z);
325  pcl::transformPointCloud(*pc_local_accum_, *pc_local_accum_, trans_eigen);
326  }
327  catch (tf2::TransformException& e)
328  {
329  ROS_INFO("Failed to transform pointcloud: %s", e.what());
330  pc_local_accum_.reset(new pcl::PointCloud<PointType>);
331  pc_accum_header_.clear();
332  return;
333  }
334  std::vector<Vec3> origins;
335  for (auto& h : pc_accum_header_)
336  {
337  try
338  {
339  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
340  frame_ids_["base_link"], msg->header.stamp, h.frame_id, h.stamp, frame_ids_["odom"]);
341  origins.push_back(Vec3(trans.transform.translation.x,
342  trans.transform.translation.y,
343  trans.transform.translation.z));
344  }
345  catch (tf2::TransformException& e)
346  {
347  ROS_INFO("Failed to transform pointcloud: %s", e.what());
348  pc_local_accum_.reset(new pcl::PointCloud<PointType>);
349  pc_accum_header_.clear();
350  return;
351  }
352  }
353 
354  const auto ts = boost::chrono::high_resolution_clock::now();
355 
356  pcl::PointCloud<PointType>::Ptr pc_local_full(new pcl::PointCloud<PointType>);
358  ds.setInputCloud(pc_local_accum_);
360  ds.filter(*pc_local_full);
361 
362  std::map<std::string, pcl::PointCloud<PointType>::Ptr> pc_locals;
363  for (auto& lm : lidar_measurements_)
364  {
365  lm.second->setGlobalLocalizationStatus(
366  params_.num_particles_, pf_->getParticleSize());
367  pc_locals[lm.first] = lm.second->filter(pc_local_full);
368  }
369 
370  if (pc_locals["likelihood"]->size() == 0)
371  {
372  ROS_ERROR("All points are filtered out. Failed to localize.");
373  return;
374  }
375  if (pc_locals["beam"] && pc_locals["beam"]->size() == 0)
376  {
377  ROS_DEBUG("All beam points are filtered out. Skipping beam model.");
378  }
379 
380  float match_ratio_min = 1.0;
381  float match_ratio_max = 0.0;
384  auto measure_func = [this, &pc_locals,
385  &origins,
386  &odom_error_lin_nd,
387  &match_ratio_min, &match_ratio_max](const State6DOF& s) -> float
388  {
389  float likelihood = 1;
390  std::map<std::string, float> qualities;
391  for (auto& lm : lidar_measurements_)
392  {
393  const LidarMeasurementResult result = lm.second->measure(
394  kdtree_, pc_locals[lm.first], origins, s);
395  likelihood *= result.likelihood;
396  qualities[lm.first] = result.quality;
397  }
398  if (match_ratio_min > qualities["likelihood"])
399  match_ratio_min = qualities["likelihood"];
400  if (match_ratio_max < qualities["likelihood"])
401  match_ratio_max = qualities["likelihood"];
402 
403  // odometry error integration
404  const float odom_error =
405  odom_error_lin_nd(s.odom_err_integ_lin_.norm());
406  return likelihood * odom_error;
407  };
408  pf_->measure(measure_func);
409 
410  if (static_cast<int>(pf_->getParticleSize()) > params_.num_particles_)
411  {
412  auto bias_func = [](const State6DOF& s, float& p_bias) -> void
413  {
414  p_bias = 1.0;
415  };
416  pf_->bias(bias_func);
417  }
418  else
419  {
422  auto bias_func = [this, &nl_lin, &nl_ang](const State6DOF& s, float& p_bias) -> void
423  {
424  const float lin_diff = (s.pos_ - state_prev_.pos_).norm();
425  Vec3 axis;
426  float ang_diff;
427  (s.rot_ * state_prev_.rot_.inv()).getAxisAng(axis, ang_diff);
428  p_bias = nl_lin(lin_diff) * nl_ang(ang_diff) + 1e-6;
429  assert(std::isfinite(p_bias));
430  };
431  pf_->bias(bias_func);
432  }
433  auto e = pf_->expectationBiased();
434  const auto e_max = pf_->max();
435 
436  assert(std::isfinite(e.pos_.x_));
437  assert(std::isfinite(e.pos_.y_));
438  assert(std::isfinite(e.pos_.z_));
439  assert(std::isfinite(e.rot_.x_));
440  assert(std::isfinite(e.rot_.y_));
441  assert(std::isfinite(e.rot_.z_));
442  assert(std::isfinite(e.rot_.w_));
443 
444  e.rot_.normalize();
445 
446  if (lidar_measurements_["beam"])
447  {
448  visualization_msgs::MarkerArray markers;
449 
450  pcl::PointCloud<PointType>::Ptr pc_particle_beam(new pcl::PointCloud<PointType>);
451  *pc_particle_beam = *pc_locals["beam"];
452  e.transform(*pc_particle_beam);
453  for (auto& p : pc_particle_beam->points)
454  {
455  const int beam_header_id = p.label;
456  const Vec3 pos = e.pos_ + e.rot_ * origins[beam_header_id];
457  const Vec3 end(p.x, p.y, p.z);
458 
459  visualization_msgs::Marker marker;
460  marker.header.frame_id = frame_ids_["map"];
461  marker.header.stamp = msg->header.stamp;
462  marker.ns = "Rays";
463  marker.id = markers.markers.size();
464  marker.type = visualization_msgs::Marker::LINE_STRIP;
465  marker.action = 0;
466  marker.pose.position.x = 0.0;
467  marker.pose.position.y = 0.0;
468  marker.pose.position.z = 0.0;
469  marker.pose.orientation.x = 0.0;
470  marker.pose.orientation.y = 0.0;
471  marker.pose.orientation.z = 0.0;
472  marker.pose.orientation.w = 1.0;
473  marker.scale.x = marker.scale.y = marker.scale.z = 0.04;
474  marker.lifetime = ros::Duration(0.2);
475  marker.frame_locked = true;
476  marker.points.resize(2);
477  marker.points[0].x = pos.x_;
478  marker.points[0].y = pos.y_;
479  marker.points[0].z = pos.z_;
480  marker.points[1].x = end.x_;
481  marker.points[1].y = end.y_;
482  marker.points[1].z = end.z_;
483  marker.colors.resize(2);
484  marker.colors[0].a = 0.5;
485  marker.colors[0].r = 1.0;
486  marker.colors[0].g = 0.0;
487  marker.colors[0].b = 0.0;
488  marker.colors[1].a = 0.2;
489  marker.colors[1].r = 1.0;
490  marker.colors[1].g = 0.0;
491  marker.colors[1].b = 0.0;
492 
493  markers.markers.push_back(marker);
494  }
495  const auto beam_model =
496  std::dynamic_pointer_cast<LidarMeasurementModelBeam>(
497  lidar_measurements_["beam"]);
498  const float sin_total_ref = beam_model->getSinTotalRef();
499  for (auto& p : pc_particle_beam->points)
500  {
501  const int beam_header_id = p.label;
502  Raycast<PointType> ray(
503  kdtree_,
504  e.pos_ + e.rot_ * origins[beam_header_id],
505  Vec3(p.x, p.y, p.z),
507  for (auto point : ray)
508  {
509  if (point.collision_)
510  {
511  visualization_msgs::Marker marker;
512  marker.header.frame_id = frame_ids_["map"];
513  marker.header.stamp = msg->header.stamp;
514  marker.ns = "Ray collisions";
515  marker.id = markers.markers.size();
516  marker.type = visualization_msgs::Marker::CUBE;
517  marker.action = 0;
518  marker.pose.position.x = point.pos_.x_;
519  marker.pose.position.y = point.pos_.y_;
520  marker.pose.position.z = point.pos_.z_;
521  marker.pose.orientation.x = 0.0;
522  marker.pose.orientation.y = 0.0;
523  marker.pose.orientation.z = 0.0;
524  marker.pose.orientation.w = 1.0;
525  marker.scale.x = marker.scale.y = marker.scale.z = 0.4;
526  marker.lifetime = ros::Duration(0.2);
527  marker.frame_locked = true;
528  marker.color.a = 0.8;
529  marker.color.r = 1.0;
530  marker.color.g = 0.0;
531  marker.color.b = 0.0;
532  if (point.sin_angle_ < sin_total_ref)
533  {
534  marker.color.a = 0.2;
535  }
536  markers.markers.push_back(marker);
537  break;
538  }
539  }
540  }
541 
542  pcl::PointCloud<PointType>::Ptr pc_particle(new pcl::PointCloud<PointType>);
543  *pc_particle = *pc_locals["likelihood"];
544  e.transform(*pc_particle);
545  for (auto& p : pc_particle->points)
546  {
547  visualization_msgs::Marker marker;
548  marker.header.frame_id = frame_ids_["map"];
549  marker.header.stamp = msg->header.stamp;
550  marker.ns = "Sample points";
551  marker.id = markers.markers.size();
552  marker.type = visualization_msgs::Marker::SPHERE;
553  marker.action = 0;
554  marker.pose.position.x = p.x;
555  marker.pose.position.y = p.y;
556  marker.pose.position.z = p.z;
557  marker.pose.orientation.x = 0.0;
558  marker.pose.orientation.y = 0.0;
559  marker.pose.orientation.z = 0.0;
560  marker.pose.orientation.w = 1.0;
561  marker.scale.x = marker.scale.y = marker.scale.z = 0.2;
562  marker.lifetime = ros::Duration(0.2);
563  marker.frame_locked = true;
564  marker.color.a = 1.0;
565  marker.color.r = 1.0;
566  marker.color.g = 0.0;
567  marker.color.b = 1.0;
568 
569  markers.markers.push_back(marker);
570  }
571 
572  pub_debug_marker_.publish(markers);
573  }
574 
575  Vec3 map_pos;
576  Quat map_rot;
577  map_pos = e.pos_ - e.rot_ * odom_.rot_.inv() * odom_.pos_;
578  map_rot = e.rot_ * odom_.rot_.inv();
579 
580  bool jump = false;
581  if (static_cast<int>(pf_->getParticleSize()) > params_.num_particles_)
582  {
583  jump = true;
584  state_prev_ = e;
585  }
586  else
587  {
588  Vec3 jump_axis;
589  float jump_ang;
590  float jump_dist = (e.pos_ - state_prev_.pos_).norm();
591  (e.rot_.inv() * state_prev_.rot_).getAxisAng(jump_axis, jump_ang);
592  if (jump_dist > params_.jump_dist_ ||
593  fabs(jump_ang) > params_.jump_ang_)
594  {
595  ROS_INFO("Pose jumped pos:%0.3f, ang:%0.3f", jump_dist, jump_ang);
596  jump = true;
597 
598  auto integ_reset_func = [](State6DOF& s)
599  {
600  s.odom_err_integ_lin_ = Vec3();
601  s.odom_err_integ_ang_ = Vec3();
602  };
603  pf_->predict(integ_reset_func);
604  }
605  state_prev_ = e;
606  }
607  geometry_msgs::TransformStamped trans;
608  if (has_odom_)
609  trans.header.stamp = odom_last_ + tf_tolerance_base_ + *params_.tf_tolerance_;
610  else
611  trans.header.stamp = ros::Time::now() + tf_tolerance_base_ + *params_.tf_tolerance_;
612  trans.header.frame_id = frame_ids_["map"];
613  trans.child_frame_id = frame_ids_["odom"];
614  auto rpy = map_rot.getRPY();
615  if (jump)
616  {
617  f_ang_[0]->set(rpy.x_);
618  f_ang_[1]->set(rpy.y_);
619  f_ang_[2]->set(rpy.z_);
620  f_pos_[0]->set(map_pos.x_);
621  f_pos_[1]->set(map_pos.y_);
622  f_pos_[2]->set(map_pos.z_);
623  }
624  rpy.x_ = f_ang_[0]->in(rpy.x_);
625  rpy.y_ = f_ang_[1]->in(rpy.y_);
626  rpy.z_ = f_ang_[2]->in(rpy.z_);
627  map_rot.setRPY(rpy);
628  map_pos.x_ = f_pos_[0]->in(map_pos.x_);
629  map_pos.y_ = f_pos_[1]->in(map_pos.y_);
630  map_pos.z_ = f_pos_[2]->in(map_pos.z_);
631  trans.transform.translation = tf2::toMsg(tf2::Vector3(map_pos.x_, map_pos.y_, map_pos.z_));
632  trans.transform.rotation = tf2::toMsg(tf2::Quaternion(map_rot.x_, map_rot.y_, map_rot.z_, map_rot.w_));
633 
634  std::vector<geometry_msgs::TransformStamped> transforms;
635  transforms.push_back(trans);
636 
637  e.rot_ = map_rot * odom_.rot_;
638  e.pos_ = map_pos + e.rot_ * odom_.rot_.inv() * odom_.pos_;
639 
640  assert(std::isfinite(e.pos_.x_));
641  assert(std::isfinite(e.pos_.y_));
642  assert(std::isfinite(e.pos_.z_));
643  assert(std::isfinite(e.rot_.x_));
644  assert(std::isfinite(e.rot_.y_));
645  assert(std::isfinite(e.rot_.z_));
646  assert(std::isfinite(e.rot_.w_));
647 
648  trans.header.frame_id = frame_ids_["map"];
649  trans.child_frame_id = frame_ids_["floor"];
650  trans.transform.translation = tf2::toMsg(tf2::Vector3(0.0, 0.0, e.pos_.z_));
651  trans.transform.rotation = tf2::toMsg(tf2::Quaternion(0.0, 0.0, 0.0, 1.0));
652 
653  transforms.push_back(trans);
654 
655  if (publish_tf_)
656  tfb_.sendTransform(transforms);
657 
658  auto cov = pf_->covariance();
659 
660  geometry_msgs::PoseWithCovarianceStamped pose;
661  pose.header.stamp = msg->header.stamp;
662  pose.header.frame_id = trans.header.frame_id;
663  pose.pose.pose.position.x = e.pos_.x_;
664  pose.pose.pose.position.y = e.pos_.y_;
665  pose.pose.pose.position.z = e.pos_.z_;
666  pose.pose.pose.orientation.x = e.rot_.x_;
667  pose.pose.pose.orientation.y = e.rot_.y_;
668  pose.pose.pose.orientation.z = e.rot_.z_;
669  pose.pose.pose.orientation.w = e.rot_.w_;
670  for (size_t i = 0; i < 36; i++)
671  {
672  pose.pose.covariance[i] = cov[i / 6][i % 6];
673  }
674  pub_pose_.publish(pose);
675 
676  {
677  bool fix = false;
678  Vec3 fix_axis;
679  const float fix_ang = sqrtf(cov[3][3] + cov[4][4] + cov[5][5]);
680  const float fix_dist = sqrtf(cov[0][0] + cov[1][1] + cov[2][2]);
681  ROS_DEBUG("cov: lin %0.3f ang %0.3f", fix_dist, fix_ang);
682  if (fix_dist < params_.fix_dist_ &&
683  fabs(fix_ang) < params_.fix_ang_)
684  {
685  fix = true;
686  }
687 
688  if (fix)
689  ROS_DEBUG("Localization fixed");
690  }
691 
692  if (output_pcd_)
693  {
694  pcl::PointCloud<PointType>::Ptr pc_particle(new pcl::PointCloud<PointType>);
695  *pc_particle = *pc_locals["likelihood"];
696  e.transform(*pc_particle);
697  *pc_all_accum_ += *pc_particle;
698  }
699 
700  if ((msg->header.stamp - match_output_last_ > *params_.match_output_interval_ ||
701  msg->header.stamp < match_output_last_ - ros::Duration(1.0)) &&
703  {
704  match_output_last_ = msg->header.stamp;
705 
706  sensor_msgs::PointCloud pc_match;
707  pc_match.header.stamp = msg->header.stamp;
708  pc_match.header.frame_id = frame_ids_["map"];
709  sensor_msgs::PointCloud pc_unmatch;
710  pc_unmatch.header.stamp = msg->header.stamp;
711  pc_unmatch.header.frame_id = frame_ids_["map"];
712 
713  pcl::PointCloud<PointType>::Ptr pc_local(new pcl::PointCloud<PointType>);
714  *pc_local = *pc_local_full;
715 
716  e.transform(*pc_local);
717 
718  std::vector<int> id(1);
719  std::vector<float> sqdist(1);
720  const double match_dist_sq = params_.match_output_dist_ * params_.match_output_dist_;
721  for (auto& p : pc_local->points)
722  {
723  geometry_msgs::Point32 pp;
724  pp.x = p.x;
725  pp.y = p.y;
726  pp.z = p.z;
727 
728  if (!kdtree_->radiusSearch(p, params_.unmatch_output_dist_, id, sqdist, 1))
729  {
730  pc_unmatch.points.push_back(pp);
731  }
732  else if (sqdist[0] < match_dist_sq)
733  {
734  pc_match.points.push_back(pp);
735  }
736  }
738  {
739  sensor_msgs::PointCloud2 pc2;
741  pub_matched_.publish(pc2);
742  }
744  {
745  sensor_msgs::PointCloud2 pc2;
747  pub_unmatched_.publish(pc2);
748  }
749  }
750 
752 
753  pf_->resample(State6DOF(
760 
761  std::normal_distribution<float> noise(0.0, 1.0);
762  auto update_noise_func = [this, &noise](State6DOF& s)
763  {
764  s.noise_ll_ = noise(engine_) * params_.odom_err_lin_lin_;
765  s.noise_la_ = noise(engine_) * params_.odom_err_lin_ang_;
766  s.noise_aa_ = noise(engine_) * params_.odom_err_ang_ang_;
767  s.noise_al_ = noise(engine_) * params_.odom_err_ang_lin_;
768  };
769  pf_->predict(update_noise_func);
770 
771  const auto tnow = boost::chrono::high_resolution_clock::now();
772  ROS_DEBUG("MCL (%0.3f sec.)",
773  boost::chrono::duration<float>(tnow - ts).count());
774  const auto err_integ_map = e_max.rot_ * e_max.odom_err_integ_lin_;
775  ROS_DEBUG("odom error integral lin: %0.3f, %0.3f, %0.3f, "
776  "ang: %0.3f, %0.3f, %0.3f, "
777  "pos: %0.3f, %0.3f, %0.3f, "
778  "err on map: %0.3f, %0.3f, %0.3f",
779  e_max.odom_err_integ_lin_.x_,
780  e_max.odom_err_integ_lin_.y_,
781  e_max.odom_err_integ_lin_.z_,
782  e_max.odom_err_integ_ang_.x_,
783  e_max.odom_err_integ_ang_.y_,
784  e_max.odom_err_integ_ang_.z_,
785  e_max.pos_.x_,
786  e_max.pos_.y_,
787  e_max.pos_.z_,
788  err_integ_map.x_,
789  err_integ_map.y_,
790  err_integ_map.z_);
791  ROS_DEBUG("match ratio min: %0.3f, max: %0.3f, pos: %0.3f, %0.3f, %0.3f",
792  match_ratio_min,
793  match_ratio_max,
794  e.pos_.x_,
795  e.pos_.y_,
796  e.pos_.z_);
797  if (match_ratio_max < params_.match_ratio_thresh_)
798  {
799  ROS_WARN_THROTTLE(3.0, "Low match_ratio. Expansion resetting.");
800  pf_->noise(State6DOF(
807  status.status = mcl_3dl_msgs::Status::EXPANSION_RESETTING;
808  }
809  pc_local_accum_.reset(new pcl::PointCloud<PointType>);
810  pc_accum_header_.clear();
811 
812  ros::Time localized_current = ros::Time::now();
813  float dt = (localized_current - localized_last_).toSec();
814  if (dt > 1.0)
815  dt = 1.0;
816  else if (dt < 0.0)
817  dt = 0.0;
819  localized_last_ = localized_current;
820 
821  if (static_cast<int>(pf_->getParticleSize()) > params_.num_particles_)
822  {
823  const int reduced = pf_->getParticleSize() * 0.75;
824  if (reduced > params_.num_particles_)
825  {
826  pf_->resizeParticle(reduced);
827  }
828  else
829  {
830  pf_->resizeParticle(params_.num_particles_);
831  }
832  // wait 99.7% fix (three-sigma)
834  }
836  {
838  status.status = mcl_3dl_msgs::Status::GLOBAL_LOCALIZATION;
839  }
840 
841  status.match_ratio = match_ratio_max;
842  status.particle_size = pf_->getParticleSize();
843  pub_status_.publish(status);
844  }
845  void cbLandmark(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
846  {
848  Eigen::Matrix<double, 6, 6>(
849  msg->pose.covariance.data())
850  .cast<float>());
851  const State6DOF measured(
852  Vec3(msg->pose.pose.position.x,
853  msg->pose.pose.position.y,
854  msg->pose.pose.position.z),
855  Quat(msg->pose.pose.orientation.x,
856  msg->pose.pose.orientation.y,
857  msg->pose.pose.orientation.z,
858  msg->pose.pose.orientation.w));
859  auto measure_func = [this, &measured, &nd](const State6DOF& s) -> float
860  {
861  State6DOF diff = s - measured;
862  const Vec3 rot_rpy = diff.rot_.getRPY();
863  const Eigen::Matrix<float, 6, 1> diff_vec =
864  (Eigen::MatrixXf(6, 1) << diff.pos_.x_,
865  diff.pos_.y_,
866  diff.pos_.z_,
867  rot_rpy.x_,
868  rot_rpy.y_,
869  rot_rpy.z_)
870  .finished();
871 
872  const auto n = nd(diff_vec);
873  return n;
874  };
875  pf_->measure(measure_func);
876 
877  pf_->resample(State6DOF(
884 
886  }
887  void cbImu(const sensor_msgs::Imu::ConstPtr& msg)
888  {
889  Vec3 acc;
890  acc.x_ = f_acc_[0]->in(msg->linear_acceleration.x);
891  acc.y_ = f_acc_[1]->in(msg->linear_acceleration.y);
892  acc.z_ = f_acc_[2]->in(msg->linear_acceleration.z);
893 
894  if (!has_imu_)
895  {
896  f_acc_[0]->set(0.0);
897  f_acc_[1]->set(0.0);
898  f_acc_[2]->set(0.0);
899  imu_last_ = msg->header.stamp;
900  has_imu_ = true;
901  return;
902  }
903 
904  float dt = (msg->header.stamp - imu_last_).toSec();
905  if (dt < 0.0 || dt > 5.0)
906  {
907  ROS_WARN("Detected time jump in imu. Resetting.");
908  has_imu_ = false;
909  return;
910  }
911  else if (dt > 0.05)
912  {
913  Vec3 acc_measure = acc / acc.norm();
914  try
915  {
916  geometry_msgs::Vector3 in, out;
917  in.x = acc_measure.x_;
918  in.y = acc_measure.y_;
919  in.z = acc_measure.z_;
920  // assuming imu frame is regit on base_link
921  const geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
922  frame_ids_["base_link"], msg->header.frame_id, ros::Time(0));
923  tf2::doTransform(in, out, trans);
924  acc_measure = Vec3(out.x, out.y, out.z);
925 
926  imu_quat_.x_ = msg->orientation.x;
927  imu_quat_.y_ = msg->orientation.y;
928  imu_quat_.z_ = msg->orientation.z;
929  imu_quat_.w_ = msg->orientation.w;
930  Vec3 axis;
931  float angle;
932  imu_quat_.getAxisAng(axis, angle);
933  axis = Quat(trans.transform.rotation.x,
934  trans.transform.rotation.y,
935  trans.transform.rotation.z,
936  trans.transform.rotation.w) *
937  axis;
938  imu_quat_.setAxisAng(axis, angle);
939  }
940  catch (tf2::TransformException& e)
941  {
942  return;
943  }
944 
945  imu_measurement_model_->setAccMeasure(acc_measure);
946  auto imu_measure_func = [this](const State6DOF& s) -> float
947  {
948  return imu_measurement_model_->measure(s);
949  };
950  pf_->measure(imu_measure_func);
951 
952  imu_last_ = msg->header.stamp;
953 
954  if (fake_odom_)
955  {
956  nav_msgs::Odometry::Ptr odom(new nav_msgs::Odometry);
957  odom->header.frame_id = frame_ids_["base_link"];
958  odom->header.stamp = msg->header.stamp;
959  odom->pose.pose.orientation.x = imu_quat_.x_;
960  odom->pose.pose.orientation.y = imu_quat_.y_;
961  odom->pose.pose.orientation.z = imu_quat_.z_;
962  odom->pose.pose.orientation.w = imu_quat_.w_;
963  cbOdom(odom);
964  }
965  }
966  }
967  bool cbResizeParticle(mcl_3dl_msgs::ResizeParticleRequest& request,
968  mcl_3dl_msgs::ResizeParticleResponse& response)
969  {
970  pf_->resizeParticle(request.size);
972  return true;
973  }
974  bool cbExpansionReset(std_srvs::TriggerRequest& request,
975  std_srvs::TriggerResponse& response)
976  {
977  pf_->noise(State6DOF(
985  return true;
986  }
987  bool cbGlobalLocalization(std_srvs::TriggerRequest& request,
988  std_srvs::TriggerResponse& response)
989  {
990  if (!has_map_)
991  {
992  response.success = false;
993  response.message = "No map received.";
994  return true;
995  }
996  pcl::PointCloud<PointType>::Ptr points(new pcl::PointCloud<PointType>);
997 
999  ds.setInputCloud(pc_map_);
1000  ds.setLeafSize(
1004  ds.filter(*points);
1005 
1006  pcl::KdTreeFLANN<PointType>::Ptr kdtree(new pcl::KdTreeFLANN<PointType>);
1007  kdtree->setPointRepresentation(
1008  boost::dynamic_pointer_cast<
1009  pcl::PointRepresentation<PointType>,
1010  MyPointRepresentation>(boost::make_shared<MyPointRepresentation>(point_rep_)));
1011  kdtree->setInputCloud(points);
1012 
1013  auto pc_filter = [this, kdtree](const PointType& p)
1014  {
1015  std::vector<int> id(1);
1016  std::vector<float> sqdist(1);
1017  auto p2 = p;
1018  p2.z += 0.01 + params_.global_localization_grid_;
1019 
1020  return kdtree->radiusSearch(
1021  p2, params_.global_localization_grid_, id, sqdist, 1);
1022  };
1023  points->erase(
1024  std::remove_if(points->begin(), points->end(), pc_filter),
1025  points->end());
1026 
1027  const int dir = params_.global_localization_div_yaw_;
1028  pf_->resizeParticle(points->size() * dir);
1029  auto pit = points->begin();
1030 
1031  const float prob = 1.0 / static_cast<float>(points->size());
1032  int cnt = 0;
1033  for (auto& particle : *pf_)
1034  {
1035  assert(pit != points->end());
1036  particle.probability_ = prob;
1037  particle.probability_bias_ = 1.0;
1038  particle.state_.pos_.x_ = pit->x;
1039  particle.state_.pos_.y_ = pit->y;
1040  particle.state_.pos_.z_ = pit->z;
1041  particle.state_.rot_ = Quat(Vec3(0.0, 0.0, 2.0 * M_PI * cnt / dir)) * imu_quat_;
1042  particle.state_.rot_.normalize();
1043  if (++cnt >= dir)
1044  {
1045  cnt = 0;
1046  ++pit;
1047  }
1048  }
1049  response.success = true;
1050  response.message = std::to_string(points->size()) + " particles";
1051  return true;
1052  }
1053 
1055  {
1056  geometry_msgs::PoseArray pa;
1057  if (has_odom_)
1058  pa.header.stamp = odom_last_ + tf_tolerance_base_ + *params_.tf_tolerance_;
1059  else
1060  pa.header.stamp = ros::Time::now() + tf_tolerance_base_ + *params_.tf_tolerance_;
1061  pa.header.frame_id = frame_ids_["map"];
1062  for (size_t i = 0; i < pf_->getParticleSize(); i++)
1063  {
1064  geometry_msgs::Pose pm;
1065  auto p = pf_->getParticle(i);
1066  p.rot_.normalize();
1067  pm.position.x = p.pos_.x_;
1068  pm.position.y = p.pos_.y_;
1069  pm.position.z = p.pos_.z_;
1070  pm.orientation.x = p.rot_.x_;
1071  pm.orientation.y = p.rot_.y_;
1072  pm.orientation.z = p.rot_.z_;
1073  pm.orientation.w = p.rot_.w_;
1074  pa.poses.push_back(pm);
1075  }
1076  pub_particle_.publish(pa);
1077  }
1078 
1079 public:
1081  : nh_("")
1082  , pnh_("~")
1083  , tfl_(tfbuf_)
1085  , engine_(seed_gen_())
1086  {
1087  }
1088  bool configure()
1089  {
1091 
1092  pnh_.param("fake_imu", fake_imu_, false);
1093  pnh_.param("fake_odom", fake_odom_, false);
1094  if (fake_imu_ && fake_odom_)
1095  {
1096  ROS_ERROR("One of IMU and Odometry must be enabled");
1097  return false;
1098  }
1099  if (!fake_odom_)
1100  {
1102  nh_, "odom",
1103  pnh_, "odom", 200, &MCL3dlNode::cbOdom, this);
1104  }
1105  if (!fake_imu_)
1106  {
1108  nh_, "imu/data",
1109  pnh_, "imu", 200, &MCL3dlNode::cbImu, this);
1110  }
1111 
1113  nh_, "cloud",
1114  pnh_, "cloud", 100, &MCL3dlNode::cbCloud, this);
1116  nh_, "mapcloud",
1117  pnh_, "mapcloud", 1, &MCL3dlNode::cbMapcloud, this);
1119  nh_, "mapcloud_update",
1120  pnh_, "mapcloud_update", 1, &MCL3dlNode::cbMapcloudUpdate, this);
1122  nh_, "initialpose",
1123  pnh_, "initialpose", 1, &MCL3dlNode::cbPosition, this);
1125  nh_, "mcl_measurement",
1126  pnh_, "landmark", 1, &MCL3dlNode::cbLandmark, this);
1127 
1128  pub_pose_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose", 5, false);
1129  pub_particle_ = pnh_.advertise<geometry_msgs::PoseArray>("particles", 1, true);
1130  pub_mapcloud_ = pnh_.advertise<sensor_msgs::PointCloud2>("updated_map", 1, true);
1131  pub_debug_marker_ = pnh_.advertise<visualization_msgs::MarkerArray>("debug_marker", 1, true);
1132  pub_status_ = pnh_.advertise<mcl_3dl_msgs::Status>("status", 1, true);
1133  pub_matched_ = pnh_.advertise<sensor_msgs::PointCloud2>("matched", 2, true);
1134  pub_unmatched_ = pnh_.advertise<sensor_msgs::PointCloud2>("unmatched", 2, true);
1135 
1137  nh_, "resize_mcl_particle",
1138  pnh_, "resize_particle", &MCL3dlNode::cbResizeParticle, this);
1140  nh_, "global_localization",
1141  pnh_, "global_localization", &MCL3dlNode::cbGlobalLocalization, this);
1143  nh_, "expansion_resetting",
1144  pnh_, "expansion_resetting", &MCL3dlNode::cbExpansionReset, this);
1145 
1146  pnh_.param("map_frame", frame_ids_["map"], std::string("map"));
1147  pnh_.param("robot_frame", frame_ids_["base_link"], std::string("base_link"));
1148  pnh_.param("odom_frame", frame_ids_["odom"], std::string("odom"));
1149  pnh_.param("floor_frame", frame_ids_["floor"], std::string("floor"));
1150 
1151  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/clip_near", "clip_near");
1152  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/clip_far", "clip_far");
1153  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/clip_z_min", "clip_z_min");
1154  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/clip_z_max", "clip_z_max");
1155  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/match_dist_min", "match_dist_min");
1156  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/match_dist_flat", "match_dist_flat");
1157  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/match_weight", "match_weight");
1158  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/num_points", "num_points");
1159  mcl_3dl_compat::paramRename<double>(pnh_, "likelihood/num_points_global", "num_points_global");
1160 
1161  mcl_3dl_compat::paramRename<double>(pnh_, "beam/clip_near", "clip_beam_near");
1162  mcl_3dl_compat::paramRename<double>(pnh_, "beam/clip_far", "clip_beam_far");
1163  mcl_3dl_compat::paramRename<double>(pnh_, "beam/clip_z_min", "clip_beam_z_min");
1164  mcl_3dl_compat::paramRename<double>(pnh_, "beam/clip_z_max", "clip_beam_z_max");
1165  mcl_3dl_compat::paramRename<double>(pnh_, "beam/num_points", "num_points_beam");
1166  mcl_3dl_compat::paramRename<double>(pnh_, "beam/beam_likelihood", "beam_likelihood");
1167  mcl_3dl_compat::paramRename<double>(pnh_, "beam/ang_total_ref", "ang_total_ref");
1168 
1169  pnh_.param("map_downsample_x", params_.map_downsample_x_, 0.1);
1170  pnh_.param("map_downsample_y", params_.map_downsample_y_, 0.1);
1171  pnh_.param("map_downsample_z", params_.map_downsample_z_, 0.1);
1172  pnh_.param("downsample_x", params_.downsample_x_, 0.1);
1173  pnh_.param("downsample_y", params_.downsample_y_, 0.1);
1174  pnh_.param("downsample_z", params_.downsample_z_, 0.05);
1179  pnh_.param("update_downsample_x", params_.update_downsample_x_, 0.3);
1180  pnh_.param("update_downsample_y", params_.update_downsample_y_, 0.3);
1181  pnh_.param("update_downsample_z", params_.update_downsample_z_, 0.3);
1182  double map_update_interval_t;
1183  pnh_.param("map_update_interval_interval", map_update_interval_t, 2.0);
1184  params_.map_update_interval_.reset(new ros::Duration(map_update_interval_t));
1185 
1186  float weight_f[4];
1187  pnh_.param("dist_weight_x", weight_f[0], 1.0f);
1188  pnh_.param("dist_weight_y", weight_f[1], 1.0f);
1189  pnh_.param("dist_weight_z", weight_f[2], 5.0f);
1190  weight_f[3] = 0.0;
1191  point_rep_.setRescaleValues(weight_f);
1192 
1193  pnh_.param("global_localization_grid_lin", params_.global_localization_grid_, 0.3);
1194  double grid_ang;
1195  pnh_.param("global_localization_grid_ang", grid_ang, 0.524);
1196  params_.global_localization_div_yaw_ = lroundf(2 * M_PI / grid_ang);
1197 
1198  pnh_.param("num_particles", params_.num_particles_, 64);
1200 
1201  pnh_.param("resample_var_x", params_.resample_var_x_, 0.05);
1202  pnh_.param("resample_var_y", params_.resample_var_y_, 0.05);
1203  pnh_.param("resample_var_z", params_.resample_var_z_, 0.05);
1204  pnh_.param("resample_var_roll", params_.resample_var_roll_, 0.05);
1205  pnh_.param("resample_var_pitch", params_.resample_var_pitch_, 0.05);
1206  pnh_.param("resample_var_yaw", params_.resample_var_yaw_, 0.05);
1207  pnh_.param("expansion_var_x", params_.expansion_var_x_, 0.2);
1208  pnh_.param("expansion_var_y", params_.expansion_var_y_, 0.2);
1209  pnh_.param("expansion_var_z", params_.expansion_var_z_, 0.2);
1210  pnh_.param("expansion_var_roll", params_.expansion_var_roll_, 0.05);
1211  pnh_.param("expansion_var_pitch", params_.expansion_var_pitch_, 0.05);
1212  pnh_.param("expansion_var_yaw", params_.expansion_var_yaw_, 0.05);
1213  pnh_.param("match_ratio_thresh", params_.match_ratio_thresh_, 0.0);
1214 
1215  pnh_.param("odom_err_lin_lin", params_.odom_err_lin_lin_, 0.10);
1216  pnh_.param("odom_err_lin_ang", params_.odom_err_lin_ang_, 0.05);
1217  pnh_.param("odom_err_ang_lin", params_.odom_err_ang_lin_, 0.05);
1218  pnh_.param("odom_err_ang_ang", params_.odom_err_ang_ang_, 0.05);
1219 
1220  pnh_.param("odom_err_integ_lin_tc", params_.odom_err_integ_lin_tc_, 10.0);
1221  pnh_.param("odom_err_integ_lin_sigma", params_.odom_err_integ_lin_sigma_, 100.0);
1222  pnh_.param("odom_err_integ_ang_tc", params_.odom_err_integ_ang_tc_, 10.0);
1223  pnh_.param("odom_err_integ_ang_sigma", params_.odom_err_integ_ang_sigma_, 100.0);
1224 
1225  double x, y, z;
1226  double roll, pitch, yaw;
1227  double v_x, v_y, v_z;
1228  double v_roll, v_pitch, v_yaw;
1229  pnh_.param("init_x", x, 0.0);
1230  pnh_.param("init_y", y, 0.0);
1231  pnh_.param("init_z", z, 0.0);
1232  pnh_.param("init_roll", roll, 0.0);
1233  pnh_.param("init_pitch", pitch, 0.0);
1234  pnh_.param("init_yaw", yaw, 0.0);
1235  pnh_.param("init_var_x", v_x, 2.0);
1236  pnh_.param("init_var_y", v_y, 2.0);
1237  pnh_.param("init_var_z", v_z, 0.5);
1238  pnh_.param("init_var_roll", v_roll, 0.1);
1239  pnh_.param("init_var_pitch", v_pitch, 0.1);
1240  pnh_.param("init_var_yaw", v_yaw, 0.5);
1241  pf_->init(
1242  State6DOF(
1243  Vec3(x, y, z),
1244  Quat(Vec3(roll, pitch, yaw))),
1245  State6DOF(
1246  Vec3(v_x, v_y, v_z),
1247  Vec3(v_roll, v_pitch, v_yaw)));
1248 
1249  pnh_.param("lpf_step", params_.lpf_step_, 16.0);
1250  f_pos_[0].reset(new Filter(Filter::FILTER_LPF, params_.lpf_step_, 0.0));
1251  f_pos_[1].reset(new Filter(Filter::FILTER_LPF, params_.lpf_step_, 0.0));
1252  f_pos_[2].reset(new Filter(Filter::FILTER_LPF, params_.lpf_step_, 0.0));
1253  f_ang_[0].reset(new Filter(Filter::FILTER_LPF, params_.lpf_step_, 0.0, true));
1254  f_ang_[1].reset(new Filter(Filter::FILTER_LPF, params_.lpf_step_, 0.0, true));
1255  f_ang_[2].reset(new Filter(Filter::FILTER_LPF, params_.lpf_step_, 0.0, true));
1256 
1257  double acc_lpf_step;
1258  pnh_.param("acc_lpf_step", acc_lpf_step, 128.0);
1259  f_acc_[0].reset(new Filter(Filter::FILTER_LPF, acc_lpf_step, 0.0));
1260  f_acc_[1].reset(new Filter(Filter::FILTER_LPF, acc_lpf_step, 0.0));
1261  f_acc_[2].reset(new Filter(Filter::FILTER_LPF, acc_lpf_step, 0.0));
1262  pnh_.param("acc_var", params_.acc_var_, M_PI / 4.0); // 45 deg
1263 
1264  pnh_.param("jump_dist", params_.jump_dist_, 1.0);
1265  pnh_.param("jump_ang", params_.jump_ang_, 1.57);
1266  pnh_.param("fix_dist", params_.fix_dist_, 0.2);
1267  pnh_.param("fix_ang", params_.fix_ang_, 0.1);
1268  pnh_.param("bias_var_dist", params_.bias_var_dist_, 2.0);
1269  pnh_.param("bias_var_ang", params_.bias_var_ang_, 1.57);
1270 
1271  pnh_.param("skip_measure", params_.skip_measure_, 1);
1272  cnt_measure_ = 0;
1273  pnh_.param("accum_cloud", params_.accum_cloud_, 1);
1274  cnt_accum_ = 0;
1275 
1276  pnh_.param("match_output_dist", params_.match_output_dist_, 0.1);
1277  pnh_.param("unmatch_output_dist", params_.unmatch_output_dist_, 0.5);
1278  double match_output_interval_t;
1279  pnh_.param("match_output_interval_interval", match_output_interval_t, 0.2);
1280  params_.match_output_interval_.reset(new ros::Duration(match_output_interval_t));
1281 
1282  double tf_tolerance_t;
1283  pnh_.param("tf_tolerance", tf_tolerance_t, 0.05);
1284  params_.tf_tolerance_.reset(new ros::Duration(tf_tolerance_t));
1285 
1286  pnh_.param("publish_tf", publish_tf_, true);
1287  pnh_.param("output_pcd", output_pcd_, false);
1288 
1289  imu_quat_ = Quat(0.0, 0.0, 0.0, 1.0);
1290 
1291  has_odom_ = has_map_ = has_imu_ = false;
1292  localize_rate_.reset(new Filter(Filter::FILTER_LPF, 5.0, 0.0));
1293 
1294  lidar_measurements_["likelihood"] =
1297  lidar_measurements_["beam"] =
1305 
1306  float max_search_radius = 0;
1307  for (auto& lm : lidar_measurements_)
1308  {
1309  lm.second->loadConfig(pnh_, lm.first);
1310  max_search_radius = std::max(max_search_radius, lm.second->getMaxSearchRange());
1311  }
1312 
1313  double map_chunk;
1314  pnh_.param("map_chunk", map_chunk, 20.0);
1315  ROS_DEBUG("max_search_radius: %0.3f", max_search_radius);
1316  kdtree_.reset(new ChunkedKdtree<PointType>(map_chunk, max_search_radius));
1317  kdtree_->setEpsilon(params_.map_grid_min_ / 16);
1318  kdtree_->setPointRepresentation(
1319  boost::dynamic_pointer_cast<
1320  pcl::PointRepresentation<PointType>,
1321  MyPointRepresentation>(boost::make_shared<MyPointRepresentation>(point_rep_)));
1322 
1326 
1327  return true;
1328  }
1330  {
1331  if (output_pcd_ && pc_all_accum_)
1332  {
1333  std::cerr << "mcl_3dl: saving pcd file.";
1334  std::cerr << " (" << pc_all_accum_->points.size() << " points)" << std::endl;
1335  pcl::io::savePCDFileBinary("mcl_3dl.pcd", *pc_all_accum_);
1336  }
1337  }
1338 
1340  {
1341  if (has_map_)
1342  {
1343  const auto ts = boost::chrono::high_resolution_clock::now();
1344  if (pc_update_)
1345  {
1346  if (!pc_map2_)
1347  pc_map2_.reset(new pcl::PointCloud<PointType>);
1348  *pc_map2_ = *pc_map_ + *pc_update_;
1349  pc_update_.reset();
1350  }
1351  else
1352  {
1353  if (pc_map2_)
1354  return;
1355  pc_map2_ = pc_map_;
1356  }
1357  kdtree_->setInputCloud(pc_map2_);
1358 
1359  sensor_msgs::PointCloud2 out;
1360  pcl::toROSMsg(*pc_map2_, out);
1361  pub_mapcloud_.publish(out);
1362  const auto tnow = boost::chrono::high_resolution_clock::now();
1363  ROS_DEBUG("Map update (%0.3f sec.)",
1364  boost::chrono::duration<float>(tnow - ts).count());
1365  }
1366  }
1367 
1368 protected:
1371 
1390 
1394 
1395  std::shared_ptr<Filter> f_pos_[3];
1396  std::shared_ptr<Filter> f_ang_[3];
1397  std::shared_ptr<Filter> f_acc_[3];
1398  std::shared_ptr<Filter> localize_rate_;
1401 
1403  std::map<std::string, std::string> frame_ids_;
1406 
1410  bool has_map_;
1412  bool has_imu_;
1415  std::map<std::string, bool> frames_;
1416  std::vector<std::string> frames_v_;
1417  size_t frame_num_;
1424 
1426 
1427  pcl::PointCloud<PointType>::Ptr pc_map_;
1428  pcl::PointCloud<PointType>::Ptr pc_map2_;
1429  pcl::PointCloud<PointType>::Ptr pc_update_;
1430  pcl::PointCloud<PointType>::Ptr pc_all_accum_;
1431  pcl::PointCloud<PointType>::Ptr pc_local_accum_;
1433  std::vector<std_msgs::Header> pc_accum_header_;
1434 
1435  std::map<
1436  std::string,
1440 
1441  std::random_device seed_gen_;
1442  std::default_random_engine engine_;
1443 };
1444 } // namespace mcl_3dl
1445 
1446 int main(int argc, char* argv[])
1447 {
1448  ros::init(argc, argv, "mcl_3dl");
1449 
1450  mcl_3dl::MCL3dlNode mcl;
1451  if (!mcl.configure())
1452  {
1453  return 1;
1454  }
1455  ros::spin();
1456 
1457  return 0;
1458 }
virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
float z_
Definition: vec3.h:40
std::default_random_engine engine_
Definition: mcl_3dl.cpp:1442
ros::Time match_output_last_
Definition: mcl_3dl.cpp:1408
void setAxisAng(const Vec3 &axis, const float &ang)
Definition: quat.h:224
ros::NodeHandle pnh_
Definition: mcl_3dl.cpp:1370
ros::NodeHandle nh_
Definition: mcl_3dl.cpp:1369
State6DOF state_prev_
Definition: mcl_3dl.cpp:1418
double update_downsample_x_
Definition: parameters.h:40
std::map< std::string, std::string > frame_ids_
Definition: mcl_3dl.cpp:1403
void cbOdom(const nav_msgs::Odometry::ConstPtr &msg)
Definition: mcl_3dl.cpp:199
double expansion_var_z_
Definition: parameters.h:58
double resample_var_roll_
Definition: parameters.h:53
void publish(const boost::shared_ptr< M > &message) const
f
double odom_err_lin_ang_
Definition: parameters.h:68
float y_
Definition: quat.h:43
ros::Publisher pub_debug_marker_
Definition: mcl_3dl.cpp:1384
double unmatch_output_dist_
Definition: parameters.h:76
ros::Subscriber sub_mapcloud_
Definition: mcl_3dl.cpp:1373
XmlRpcServer s
std::shared_ptr< ChunkedKdtree > Ptr
mcl_3dl::Vec3 pos_
Definition: state_6dof.h:47
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
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:75
std::random_device seed_gen_
Definition: mcl_3dl.cpp:1441
float norm() const
Definition: vec3.h:149
double update_downsample_z_
Definition: parameters.h:42
tf2_ros::TransformBroadcaster tfb_
Definition: mcl_3dl.cpp:1393
double expansion_var_roll_
Definition: parameters.h:59
ros::ServiceServer srv_global_localization_
Definition: mcl_3dl.cpp:1388
ros::Subscriber sub_cloud_
Definition: mcl_3dl.cpp:1372
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
std::shared_ptr< Filter > f_acc_[3]
Definition: mcl_3dl.cpp:1397
ros::Subscriber sub_odom_
Definition: mcl_3dl.cpp:1375
double map_downsample_x_
Definition: parameters.h:37
ros::Publisher pub_status_
Definition: mcl_3dl.cpp:1385
pcl::PointCloud< PointType >::Ptr pc_update_
Definition: mcl_3dl.cpp:1429
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
std::map< std::string, LidarMeasurementModelBase::Ptr > lidar_measurements_
Definition: mcl_3dl.cpp:1437
ChunkedKdtree< PointType >::Ptr kdtree_
Definition: mcl_3dl.cpp:1432
pcl::PointCloud< PointType >::Ptr pc_map2_
Definition: mcl_3dl.cpp:1428
std::shared_ptr< ros::Duration > map_update_interval_
Definition: parameters.h:71
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:1391
ros::Publisher pub_particle_
Definition: mcl_3dl.cpp:1379
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
ros::Subscriber sub_mapcloud_update_
Definition: mcl_3dl.cpp:1374
Parameters params_
Definition: mcl_3dl.cpp:1402
std::shared_ptr< Filter > localize_rate_
Definition: mcl_3dl.cpp:1398
double global_localization_grid_
Definition: parameters.h:45
double odom_err_ang_ang_
Definition: parameters.h:70
void cbMapUpdateTimer(const ros::TimerEvent &event)
Definition: mcl_3dl.cpp:1339
double expansion_var_y_
Definition: parameters.h:57
void normalize()
Definition: quat.h:182
bool fromROSMsg(const sensor_msgs::PointCloud2 &msg, pcl::PointCloud< PointT > &pc)
ros::ServiceServer srv_expansion_reset_
Definition: mcl_3dl.cpp:1389
ros::Time localized_last_
Definition: mcl_3dl.cpp:1399
void cbLandmark(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
Definition: mcl_3dl.cpp:845
#define ROS_WARN_THROTTLE(period,...)
double map_downsample_y_
Definition: parameters.h:38
#define ROS_INFO(...)
float w_
Definition: quat.h:45
bool param(const std::string &param_name, T &param_val, const T &default_val) const
float y_
Definition: vec3.h:39
ros::Publisher pub_unmatched_
Definition: mcl_3dl.cpp:1383
void getAxisAng(Vec3 &axis, float &ang) const
Definition: quat.h:234
std::vector< std::string > frames_v_
Definition: mcl_3dl.cpp:1416
ros::Subscriber sub_landmark_
Definition: mcl_3dl.cpp:1378
std::shared_ptr< Filter > f_ang_[3]
Definition: mcl_3dl.cpp:1396
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
MotionPredictionModelBase::Ptr motion_prediction_model_
Definition: mcl_3dl.cpp:1439
ros::Publisher pub_matched_
Definition: mcl_3dl.cpp:1382
std::shared_ptr< LidarMeasurementModelBase > Ptr
TFSIMD_FORCE_INLINE const tfScalar & x() const
pcl::PointCloud< PointType >::Ptr pc_local_accum_
Definition: mcl_3dl.cpp:1431
bool cbExpansionReset(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
Definition: mcl_3dl.cpp:974
Quat inv() const
Definition: quat.h:190
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double odom_err_integ_lin_tc_
Definition: parameters.h:80
double resample_var_yaw_
Definition: parameters.h:55
tf2_ros::TransformListener tfl_
Definition: mcl_3dl.cpp:1392
double odom_err_lin_lin_
Definition: parameters.h:67
void sendTransform(const geometry_msgs::TransformStamped &transform)
virtual void copyToFloatArray(const PointType &p, float *out) const
Definition: mcl_3dl.cpp:111
double expansion_var_yaw_
Definition: parameters.h:61
TFSIMD_FORCE_INLINE const tfScalar & z() const
State6DOF odom_prev_
Definition: mcl_3dl.cpp:1414
mcl_3dl::Quat rot_
Definition: state_6dof.h:48
void cbMapcloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: mcl_3dl.cpp:118
B toMsg(const A &a)
double map_downsample_z_
Definition: parameters.h:39
ros::Subscriber sub_imu_
Definition: mcl_3dl.cpp:1376
ImuMeasurementModelBase::Ptr imu_measurement_model_
Definition: mcl_3dl.cpp:1438
double resample_var_z_
Definition: parameters.h:52
double odom_err_ang_lin_
Definition: parameters.h:69
void checkCompatMode()
Definition: compatibility.h:62
std::shared_ptr< ImuMeasurementModelBase > Ptr
int main(int argc, char *argv[])
Definition: mcl_3dl.cpp:1446
float x_
Definition: vec3.h:38
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())
uint32_t getNumSubscribers() const
static bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
double resample_var_y_
Definition: parameters.h:51
void setRPY(const Vec3 &rpy)
Definition: quat.h:210
ros::Time odom_last_
Definition: mcl_3dl.cpp:1409
double expansion_var_x_
Definition: parameters.h:56
std::vector< std_msgs::Header > pc_accum_header_
Definition: mcl_3dl.cpp:1433
MyPointRepresentation point_rep_
Definition: mcl_3dl.cpp:1425
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
std::map< std::string, bool > frames_
Definition: mcl_3dl.cpp:1415
static Time now()
double expansion_var_pitch_
Definition: parameters.h:60
double odom_err_integ_ang_tc_
Definition: parameters.h:82
ros::Publisher pub_mapcloud_
Definition: mcl_3dl.cpp:1380
double match_ratio_thresh_
Definition: parameters.h:62
ros::Timer map_update_timer_
Definition: mcl_3dl.cpp:1386
std::shared_ptr< Filter > f_pos_[3]
Definition: mcl_3dl.cpp:1395
void cbPosition(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
Definition: mcl_3dl.cpp:159
ros::Time imu_last_
Definition: mcl_3dl.cpp:1419
ros::Duration tf_tolerance_base_
Definition: mcl_3dl.cpp:1400
void cbImu(const sensor_msgs::Imu::ConstPtr &msg)
Definition: mcl_3dl.cpp:887
pcl::PointCloud< PointType >::Ptr pc_map_
Definition: mcl_3dl.cpp:1427
std::shared_ptr< pf::ParticleFilter< State6DOF, float, ParticleWeightedMeanQuat > > pf_
Definition: mcl_3dl.cpp:99
std::shared_ptr< ros::Duration > match_output_interval_
Definition: parameters.h:84
bool cbResizeParticle(mcl_3dl_msgs::ResizeParticleRequest &request, mcl_3dl_msgs::ResizeParticleResponse &response)
Definition: mcl_3dl.cpp:967
#define ROS_ERROR(...)
std::shared_ptr< ros::Duration > tf_tolerance_
Definition: parameters.h:85
Vec3 getRPY() const
Definition: quat.h:194
ros::Publisher pub_pose_
Definition: mcl_3dl.cpp:1381
double odom_err_integ_lin_sigma_
Definition: parameters.h:81
float z_
Definition: quat.h:44
void cbMapcloudUpdate(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: mcl_3dl.cpp:145
double update_downsample_y_
Definition: parameters.h:41
int global_localization_div_yaw_
Definition: parameters.h:46
ros::ServiceServer srv_particle_size_
Definition: mcl_3dl.cpp:1387
size_t global_localization_fix_cnt_
Definition: mcl_3dl.cpp:1423
double odom_err_integ_ang_sigma_
Definition: parameters.h:83
double resample_var_x_
Definition: parameters.h:50
ros::Subscriber sub_position_
Definition: mcl_3dl.cpp:1377
pcl::PointCloud< PointType >::Ptr pc_all_accum_
Definition: mcl_3dl.cpp:1430
float x_
Definition: quat.h:42
bool cbGlobalLocalization(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
Definition: mcl_3dl.cpp:987
double resample_var_pitch_
Definition: parameters.h:54
#define ROS_DEBUG(...)
std::shared_ptr< MotionPredictionModelBase > Ptr
void cbCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: mcl_3dl.cpp:247


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36