37 #include <boost/chrono.hpp> 38 #include <boost/shared_ptr.hpp> 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> 60 #include <pcl/point_types.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> 99 std::shared_ptr<pf::ParticleFilter<State6DOF, float, ParticleWeightedMeanQuat>>
pf_;
103 using pcl::PointRepresentation<PointType>::nr_dimensions_;
118 void cbMapcloud(
const sensor_msgs::PointCloud2::ConstPtr& msg)
121 pcl::PointCloud<PointType>::Ptr pc_tmp(
new pcl::PointCloud<PointType>);
128 pc_map_.reset(
new pcl::PointCloud<PointType>);
132 ds.setInputCloud(pc_tmp);
140 ROS_INFO(
"map original: %d points", (
int)pc_tmp->points.size());
148 pcl::PointCloud<PointType>::Ptr pc_tmp(
new pcl::PointCloud<PointType>);
152 pc_update_.reset(
new pcl::PointCloud<PointType>);
154 ds.setInputCloud(pc_tmp);
159 void cbPosition(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
161 geometry_msgs::PoseStamped pose_in, pose;
162 pose_in.header = msg->header;
163 pose_in.pose = msg->pose.pose;
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)),
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])));
191 s.odom_err_integ_lin_ =
Vec3();
192 s.odom_err_integ_ang_ =
Vec3();
194 pf_->predict(integ_reset_func);
199 void cbOdom(
const nav_msgs::Odometry::ConstPtr& msg)
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));
217 const float dt = (msg->header.stamp -
odom_last_).toSec();
218 if (dt < 0.0 || dt > 5.0)
220 ROS_WARN(
"Detected time jump in odometry. Resetting.");
231 pf_->predict(prediction_func);
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;
247 void cbCloud(
const sensor_msgs::PointCloud2::ConstPtr& msg)
249 mcl_3dl_msgs::Status status;
251 status.status = mcl_3dl_msgs::Status::NORMAL;
257 frames_[msg->header.frame_id] =
true;
258 frames_v_.push_back(msg->header.frame_id);
261 sensor_msgs::PointCloud2 pc_bl;
270 ROS_INFO(
"Failed to transform pointcloud: %s", e.what());
275 pcl::PointCloud<PointType>::Ptr pc_tmp(
new pcl::PointCloud<PointType>);
279 for (
auto& p : pc_tmp->points)
315 const Eigen::Affine3f trans_eigen =
316 Eigen::Translation3f(
317 trans.transform.translation.x,
318 trans.transform.translation.y,
319 trans.transform.translation.z) *
321 trans.transform.rotation.w,
322 trans.transform.rotation.x,
323 trans.transform.rotation.y,
324 trans.transform.rotation.z);
329 ROS_INFO(
"Failed to transform pointcloud: %s", e.what());
334 std::vector<Vec3> origins;
341 origins.push_back(
Vec3(trans.transform.translation.x,
342 trans.transform.translation.y,
343 trans.transform.translation.z));
347 ROS_INFO(
"Failed to transform pointcloud: %s", e.what());
349 pc_accum_header_.clear();
354 const auto ts = boost::chrono::high_resolution_clock::now();
356 pcl::PointCloud<PointType>::Ptr pc_local_full(
new pcl::PointCloud<PointType>);
360 ds.
filter(*pc_local_full);
362 std::map<std::string, pcl::PointCloud<PointType>::Ptr> pc_locals;
365 lm.second->setGlobalLocalizationStatus(
367 pc_locals[lm.first] = lm.second->filter(pc_local_full);
370 if (pc_locals[
"likelihood"]->size() == 0)
372 ROS_ERROR(
"All points are filtered out. Failed to localize.");
375 if (pc_locals[
"beam"] && pc_locals[
"beam"]->size() == 0)
377 ROS_DEBUG(
"All beam points are filtered out. Skipping beam model.");
380 float match_ratio_min = 1.0;
381 float match_ratio_max = 0.0;
384 auto measure_func = [
this, &pc_locals,
387 &match_ratio_min, &match_ratio_max](
const State6DOF&
s) ->
float 389 float likelihood = 1;
390 std::map<std::string, float> qualities;
391 for (
auto& lm : lidar_measurements_)
394 kdtree_, pc_locals[lm.first], origins,
s);
396 qualities[lm.first] = result.
quality;
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"];
404 const float odom_error =
405 odom_error_lin_nd(
s.odom_err_integ_lin_.norm());
406 return likelihood * odom_error;
408 pf_->measure(measure_func);
412 auto bias_func = [](
const State6DOF&
s,
float& p_bias) ->
void 416 pf_->bias(bias_func);
422 auto bias_func = [
this, &nl_lin, &nl_ang](
const State6DOF&
s,
float& p_bias) ->
void 428 p_bias = nl_lin(lin_diff) * nl_ang(ang_diff) + 1e-6;
429 assert(std::isfinite(p_bias));
431 pf_->bias(bias_func);
433 auto e = pf_->expectationBiased();
434 const auto e_max = pf_->max();
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_));
446 if (lidar_measurements_[
"beam"])
448 visualization_msgs::MarkerArray markers;
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)
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);
459 visualization_msgs::Marker marker;
461 marker.header.stamp = msg->header.stamp;
463 marker.id = markers.markers.size();
464 marker.type = visualization_msgs::Marker::LINE_STRIP;
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;
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;
493 markers.markers.push_back(marker);
495 const auto beam_model =
497 lidar_measurements_[
"beam"]);
499 for (
auto& p : pc_particle_beam->points)
501 const int beam_header_id = p.label;
504 e.pos_ + e.rot_ * origins[beam_header_id],
507 for (
auto point : ray)
509 if (point.collision_)
511 visualization_msgs::Marker marker;
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;
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;
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)
534 marker.color.a = 0.2;
536 markers.markers.push_back(marker);
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)
547 visualization_msgs::Marker marker;
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;
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;
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;
569 markers.markers.push_back(marker);
595 ROS_INFO(
"Pose jumped pos:%0.3f, ang:%0.3f", jump_dist, jump_ang);
600 s.odom_err_integ_lin_ =
Vec3();
601 s.odom_err_integ_ang_ =
Vec3();
603 pf_->predict(integ_reset_func);
607 geometry_msgs::TransformStamped trans;
614 auto rpy = map_rot.
getRPY();
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_);
631 trans.transform.translation =
tf2::toMsg(tf2::Vector3(map_pos.
x_, map_pos.
y_, map_pos.
z_));
634 std::vector<geometry_msgs::TransformStamped> transforms;
635 transforms.push_back(trans);
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_));
650 trans.transform.translation =
tf2::toMsg(tf2::Vector3(0.0, 0.0, e.pos_.z_));
653 transforms.push_back(trans);
658 auto cov = pf_->covariance();
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++)
672 pose.pose.covariance[i] = cov[i / 6][i % 6];
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);
694 pcl::PointCloud<PointType>::Ptr pc_particle(
new pcl::PointCloud<PointType>);
695 *pc_particle = *pc_locals[
"likelihood"];
696 e.transform(*pc_particle);
706 sensor_msgs::PointCloud pc_match;
707 pc_match.header.stamp = msg->header.stamp;
709 sensor_msgs::PointCloud pc_unmatch;
710 pc_unmatch.header.stamp = msg->header.stamp;
711 pc_unmatch.header.frame_id =
frame_ids_[
"map"];
713 pcl::PointCloud<PointType>::Ptr pc_local(
new pcl::PointCloud<PointType>);
714 *pc_local = *pc_local_full;
716 e.transform(*pc_local);
718 std::vector<int> id(1);
719 std::vector<float> sqdist(1);
721 for (
auto& p : pc_local->points)
723 geometry_msgs::Point32 pp;
730 pc_unmatch.points.push_back(pp);
732 else if (sqdist[0] < match_dist_sq)
734 pc_match.points.push_back(pp);
739 sensor_msgs::PointCloud2 pc2;
745 sensor_msgs::PointCloud2 pc2;
761 std::normal_distribution<float> noise(0.0, 1.0);
762 auto update_noise_func = [
this, &noise](
State6DOF&
s)
769 pf_->predict(update_noise_func);
771 const auto tnow = boost::chrono::high_resolution_clock::now();
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_,
791 ROS_DEBUG(
"match ratio min: %0.3f, max: %0.3f, pos: %0.3f, %0.3f, %0.3f",
807 status.status = mcl_3dl_msgs::Status::EXPANSION_RESETTING;
810 pc_accum_header_.clear();
823 const int reduced = pf_->getParticleSize() * 0.75;
826 pf_->resizeParticle(reduced);
838 status.status = mcl_3dl_msgs::Status::GLOBAL_LOCALIZATION;
841 status.match_ratio = match_ratio_max;
842 status.particle_size = pf_->getParticleSize();
845 void cbLandmark(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
848 Eigen::Matrix<double, 6, 6>(
849 msg->pose.covariance.data())
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 863 const Eigen::Matrix<float, 6, 1> diff_vec =
864 (Eigen::MatrixXf(6, 1) << diff.
pos_.
x_,
872 const auto n = nd(diff_vec);
875 pf_->measure(measure_func);
887 void cbImu(
const sensor_msgs::Imu::ConstPtr& msg)
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);
904 float dt = (msg->header.stamp -
imu_last_).toSec();
905 if (dt < 0.0 || dt > 5.0)
907 ROS_WARN(
"Detected time jump in imu. Resetting.");
913 Vec3 acc_measure = acc / acc.
norm();
916 geometry_msgs::Vector3 in, out;
917 in.x = acc_measure.
x_;
918 in.y = acc_measure.
y_;
919 in.z = acc_measure.
z_;
924 acc_measure =
Vec3(out.x, out.y, out.z);
933 axis =
Quat(trans.transform.rotation.x,
934 trans.transform.rotation.y,
935 trans.transform.rotation.z,
936 trans.transform.rotation.w) *
946 auto imu_measure_func = [
this](
const State6DOF&
s) ->
float 950 pf_->measure(imu_measure_func);
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;
968 mcl_3dl_msgs::ResizeParticleResponse& response)
970 pf_->resizeParticle(request.size);
975 std_srvs::TriggerResponse& response)
988 std_srvs::TriggerResponse& response)
992 response.success =
false;
993 response.message =
"No map received.";
996 pcl::PointCloud<PointType>::Ptr points(
new pcl::PointCloud<PointType>);
1006 pcl::KdTreeFLANN<PointType>::Ptr kdtree(
new pcl::KdTreeFLANN<PointType>);
1007 kdtree->setPointRepresentation(
1008 boost::dynamic_pointer_cast<
1009 pcl::PointRepresentation<PointType>,
1011 kdtree->setInputCloud(points);
1013 auto pc_filter = [
this, kdtree](
const PointType& p)
1015 std::vector<int> id(1);
1016 std::vector<float> sqdist(1);
1020 return kdtree->radiusSearch(
1024 std::remove_if(points->begin(), points->end(), pc_filter),
1028 pf_->resizeParticle(points->size() * dir);
1029 auto pit = points->begin();
1031 const float prob = 1.0 /
static_cast<float>(points->size());
1033 for (
auto& particle : *pf_)
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_;
1049 response.success =
true;
1050 response.message = std::to_string(points->size()) +
" particles";
1056 geometry_msgs::PoseArray pa;
1062 for (
size_t i = 0; i < pf_->getParticleSize(); i++)
1064 geometry_msgs::Pose pm;
1065 auto p = pf_->getParticle(i);
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);
1096 ROS_ERROR(
"One of IMU and Odometry must be enabled");
1119 nh_,
"mapcloud_update",
1125 nh_,
"mcl_measurement",
1137 nh_,
"resize_mcl_particle",
1140 nh_,
"global_localization",
1143 nh_,
"expansion_resetting",
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");
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");
1182 double map_update_interval_t;
1183 pnh_.param(
"map_update_interval_interval", map_update_interval_t, 2.0);
1187 pnh_.param(
"dist_weight_x", weight_f[0], 1.0
f);
1188 pnh_.param(
"dist_weight_y", weight_f[1], 1.0
f);
1189 pnh_.param(
"dist_weight_z", weight_f[2], 5.0
f);
1195 pnh_.param(
"global_localization_grid_ang", grid_ang, 0.524);
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);
1246 Vec3(v_x, v_y, v_z),
1247 Vec3(v_roll, v_pitch, v_yaw)));
1257 double acc_lpf_step;
1258 pnh_.param(
"acc_lpf_step", acc_lpf_step, 128.0);
1278 double match_output_interval_t;
1279 pnh_.param(
"match_output_interval_interval", match_output_interval_t, 0.2);
1282 double tf_tolerance_t;
1283 pnh_.param(
"tf_tolerance", tf_tolerance_t, 0.05);
1306 float max_search_radius = 0;
1309 lm.second->loadConfig(pnh_, lm.first);
1310 max_search_radius = std::max(max_search_radius, lm.second->getMaxSearchRange());
1314 pnh_.param(
"map_chunk", map_chunk, 20.0);
1315 ROS_DEBUG(
"max_search_radius: %0.3f", max_search_radius);
1318 kdtree_->setPointRepresentation(
1319 boost::dynamic_pointer_cast<
1320 pcl::PointRepresentation<PointType>,
1333 std::cerr <<
"mcl_3dl: saving pcd file.";
1334 std::cerr <<
" (" <<
pc_all_accum_->points.size() <<
" points)" << std::endl;
1343 const auto ts = boost::chrono::high_resolution_clock::now();
1347 pc_map2_.reset(
new pcl::PointCloud<PointType>);
1359 sensor_msgs::PointCloud2 out;
1362 const auto tnow = boost::chrono::high_resolution_clock::now();
1364 boost::chrono::duration<float>(tnow - ts).count());
virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
std::default_random_engine engine_
ros::Time match_output_last_
void setAxisAng(const Vec3 &axis, const float &ang)
double update_downsample_x_
std::map< std::string, std::string > frame_ids_
void cbOdom(const nav_msgs::Odometry::ConstPtr &msg)
double resample_var_roll_
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_debug_marker_
double unmatch_output_dist_
ros::Subscriber sub_mapcloud_
std::shared_ptr< ChunkedKdtree > Ptr
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_
std::random_device seed_gen_
double update_downsample_z_
tf2_ros::TransformBroadcaster tfb_
double expansion_var_roll_
ros::ServiceServer srv_global_localization_
ros::Subscriber sub_cloud_
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::shared_ptr< Filter > f_acc_[3]
ros::Subscriber sub_odom_
ros::Publisher pub_status_
pcl::PointCloud< PointType >::Ptr pc_update_
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_
ChunkedKdtree< PointType >::Ptr kdtree_
pcl::PointCloud< PointType >::Ptr pc_map2_
std::shared_ptr< ros::Duration > map_update_interval_
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)
ros::Publisher pub_particle_
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
ros::Subscriber sub_mapcloud_update_
std::shared_ptr< Filter > localize_rate_
double global_localization_grid_
void cbMapUpdateTimer(const ros::TimerEvent &event)
bool fromROSMsg(const sensor_msgs::PointCloud2 &msg, pcl::PointCloud< PointT > &pc)
ros::ServiceServer srv_expansion_reset_
ros::Time localized_last_
void cbLandmark(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
#define ROS_WARN_THROTTLE(period,...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Publisher pub_unmatched_
void getAxisAng(Vec3 &axis, float &ang) const
std::vector< std::string > frames_v_
ros::Subscriber sub_landmark_
std::shared_ptr< Filter > f_ang_[3]
float getSinTotalRef() const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
MotionPredictionModelBase::Ptr motion_prediction_model_
ros::Publisher pub_matched_
std::shared_ptr< LidarMeasurementModelBase > Ptr
TFSIMD_FORCE_INLINE const tfScalar & x() const
pcl::PointCloud< PointType >::Ptr pc_local_accum_
bool cbExpansionReset(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double odom_err_integ_lin_tc_
tf2_ros::TransformListener tfl_
virtual void copyToFloatArray(const PointType &p, float *out) const
double expansion_var_yaw_
TFSIMD_FORCE_INLINE const tfScalar & z() const
void cbMapcloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
ImuMeasurementModelBase::Ptr imu_measurement_model_
std::shared_ptr< ImuMeasurementModelBase > Ptr
int main(int argc, char *argv[])
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)
void setRPY(const Vec3 &rpy)
std::vector< std_msgs::Header > pc_accum_header_
MyPointRepresentation point_rep_
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
std::map< std::string, bool > frames_
double expansion_var_pitch_
double odom_err_integ_ang_tc_
ros::Publisher pub_mapcloud_
double match_ratio_thresh_
ros::Timer map_update_timer_
std::shared_ptr< Filter > f_pos_[3]
void cbPosition(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
ros::Duration tf_tolerance_base_
void cbImu(const sensor_msgs::Imu::ConstPtr &msg)
pcl::PointCloud< PointType >::Ptr pc_map_
std::shared_ptr< pf::ParticleFilter< State6DOF, float, ParticleWeightedMeanQuat > > pf_
std::shared_ptr< ros::Duration > match_output_interval_
bool cbResizeParticle(mcl_3dl_msgs::ResizeParticleRequest &request, mcl_3dl_msgs::ResizeParticleResponse &response)
std::shared_ptr< ros::Duration > tf_tolerance_
double odom_err_integ_lin_sigma_
void cbMapcloudUpdate(const sensor_msgs::PointCloud2::ConstPtr &msg)
double update_downsample_y_
int global_localization_div_yaw_
ros::ServiceServer srv_particle_size_
size_t global_localization_fix_cnt_
double odom_err_integ_ang_sigma_
ros::Subscriber sub_position_
pcl::PointCloud< PointType >::Ptr pc_all_accum_
bool cbGlobalLocalization(std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
double resample_var_pitch_
std::shared_ptr< MotionPredictionModelBase > Ptr
void cbCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)