42 #include <boost/chrono.hpp> 43 #include <boost/shared_ptr.hpp> 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> 67 #include <pcl/point_types.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> 107 std::shared_ptr<pf::ParticleFilter<State6DOF, float, ParticleWeightedMeanQuat, std::default_random_engine>>
pf_;
111 using pcl::PointRepresentation<PointType>::nr_dimensions_;
127 void cbMapcloud(
const sensor_msgs::PointCloud2::ConstPtr& msg)
130 pcl::PointCloud<PointType>::Ptr pc_tmp(
new pcl::PointCloud<PointType>);
144 pcl::PointCloud<PointType>::Ptr pc_tmp(
new pcl::PointCloud<PointType>);
148 pc_update_.reset(
new pcl::PointCloud<PointType>);
149 pcl::VoxelGrid<PointType> ds;
150 ds.setInputCloud(pc_tmp);
155 void cbPosition(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
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)
164 ROS_ERROR(
"Discarded invalid initialpose. The orientation must be unit quaternion.");
168 geometry_msgs::PoseStamped pose_in, pose;
169 pose_in.header = msg->header;
170 pose_in.pose = msg->pose.pose;
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));
187 pf_->initUsingNoiseGenerator(noise_gen);
192 s.odom_err_integ_lin_ =
Vec3();
193 s.odom_err_integ_ang_ =
Vec3();
195 pf_->predict(integ_reset_func);
200 void cbOdom(
const nav_msgs::Odometry::ConstPtr& msg)
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));
218 const float dt = (msg->header.stamp -
odom_last_).toSec();
219 if (dt < 0.0 || dt > 5.0)
221 ROS_WARN(
"Detected time jump in odometry. Resetting.");
232 pf_->predict(prediction_func);
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;
248 void cbCloud(
const sensor_msgs::PointCloud2::ConstPtr& msg)
250 status_ = mcl_3dl_msgs::Status();
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;
260 msg->header.frame_id,
274 bool accumCloud(
const sensor_msgs::PointCloud2::ConstPtr& msg)
276 sensor_msgs::PointCloud2 pc_bl;
285 ROS_INFO(
"Failed to transform pointcloud: %s", e.what());
288 pcl::PointCloud<PointType>::Ptr pc_tmp(
new pcl::PointCloud<PointType>);
291 ROS_INFO(
"Failed to convert pointcloud");
295 for (
auto& p : pc_tmp->points)
314 ROS_ERROR(
"MCL measure function is called without available pointcloud");
326 const Eigen::Affine3f trans_eigen =
327 Eigen::Translation3f(
328 trans.transform.translation.x,
329 trans.transform.translation.y,
330 trans.transform.translation.z) *
332 trans.transform.rotation.w,
333 trans.transform.rotation.x,
334 trans.transform.rotation.y,
335 trans.transform.rotation.z);
340 ROS_INFO(
"Failed to transform pointcloud: %s", e.what());
343 std::vector<Vec3> origins;
350 origins.push_back(
Vec3(trans.transform.translation.x,
351 trans.transform.translation.y,
352 trans.transform.translation.z));
356 ROS_INFO(
"Failed to transform pointcloud: %s", e.what());
361 const auto ts = boost::chrono::high_resolution_clock::now();
363 pcl::PointCloud<PointType>::Ptr pc_local_full(
new pcl::PointCloud<PointType>);
364 pcl::VoxelGrid<PointType> ds;
367 ds.filter(*pc_local_full);
369 std::map<std::string, pcl::PointCloud<PointType>::Ptr> pc_locals;
372 lm.second->setGlobalLocalizationStatus(
377 const State6DOF prev_mean = pf_->expectation();
378 const float cov_ratio = std::max(0.1
f, static_cast<float>(
params_.
num_particles_) / pf_->getParticleSize());
379 const std::vector<State6DOF> prev_cov = pf_->covariance(1.0, cov_ratio);
383 pc_locals[lm.first] = lm.second->filter(pc_local_full);
386 if (pc_locals[
"likelihood"]->size() == 0)
388 ROS_ERROR(
"All points are filtered out. Failed to localize.");
389 status_.error = mcl_3dl_msgs::Status::ERROR_POINTS_NOT_FOUND;
394 if (pc_locals[
"beam"] && pc_locals[
"beam"]->size() == 0)
396 ROS_DEBUG(
"All beam points are filtered out. Skipping beam model.");
399 float match_ratio_min = 1.0;
400 float match_ratio_max = 0.0;
403 auto measure_func = [
this, &pc_locals,
406 &match_ratio_min, &match_ratio_max](
const State6DOF&
s) ->
float 408 float likelihood = 1;
409 std::map<std::string, float> qualities;
410 for (
auto& lm : lidar_measurements_)
413 kdtree_, pc_locals[lm.first], origins,
s);
415 qualities[lm.first] = result.
quality;
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"];
423 const float odom_error =
424 odom_error_lin_nd(
s.odom_err_integ_lin_.norm());
425 return likelihood * odom_error;
427 pf_->measure(measure_func);
431 auto bias_func = [](
const State6DOF&
s,
float& p_bias) ->
void 435 pf_->bias(bias_func);
441 auto bias_func = [
this, &nl_lin, &nl_ang](
const State6DOF&
s,
float& p_bias) ->
void 447 p_bias = nl_lin(lin_diff) * nl_ang(ang_diff) + 1e-6;
448 assert(std::isfinite(p_bias));
450 pf_->bias(bias_func);
452 auto e = pf_->expectationBiased();
453 const auto e_max = pf_->max();
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_));
465 if (lidar_measurements_[
"beam"])
467 visualization_msgs::MarkerArray markers;
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);
473 for (
auto& p : pc_particle_beam->points)
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);
483 visualization_msgs::Marker marker;
485 marker.header.stamp = header.stamp;
486 marker.ns =
"Ray collisions";
487 marker.id = markers.markers.size();
488 marker.type = visualization_msgs::Marker::CUBE;
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;
499 marker.frame_locked =
true;
503 marker.color.a = 0.8;
504 marker.color.r = 0.0;
505 marker.color.g = 1.0;
506 marker.color.b = 0.0;
509 marker.color.a = 0.8;
510 marker.color.r = 1.0;
511 marker.color.g = 0.0;
512 marker.color.b = 0.0;
515 marker.color.a = 0.2;
516 marker.color.r = 0.0;
517 marker.color.g = 1.0;
518 marker.color.b = 0.0;
523 markers.markers.push_back(marker);
526 visualization_msgs::Marker marker;
528 marker.header.stamp = header.stamp;
530 marker.id = markers.markers.size();
531 marker.type = visualization_msgs::Marker::LINE_STRIP;
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;
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);
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;
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;
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;
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;
595 markers.markers.push_back(marker);
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)
603 visualization_msgs::Marker marker;
605 marker.header.stamp = header.stamp;
606 marker.ns =
"Sample points";
607 marker.id = markers.markers.size();
608 marker.type = visualization_msgs::Marker::SPHERE;
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;
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;
625 markers.markers.push_back(marker);
651 ROS_INFO(
"Pose jumped pos:%0.3f, ang:%0.3f", jump_dist, jump_ang);
656 s.odom_err_integ_lin_ =
Vec3();
657 s.odom_err_integ_ang_ =
Vec3();
659 pf_->predict(integ_reset_func);
663 geometry_msgs::TransformStamped trans;
670 const auto rpy = map_rot.
getRPY();
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_));
681 std::vector<geometry_msgs::TransformStamped> transforms;
682 transforms.push_back(trans);
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_));
697 trans.transform.translation =
tf2::toMsg(tf2::Vector3(0.0, 0.0, e.pos_.z_));
700 transforms.push_back(trans);
707 auto cov = pf_->covariance(
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++)
724 pose.pose.covariance[i] = cov[i / 6][i % 6];
734 status_.convergence_status = mcl_3dl_msgs::Status::CONVERGENCE_STATUS_LARGE_STD_VALUE;
738 if (
status_.convergence_status != mcl_3dl_msgs::Status::CONVERGENCE_STATUS_LARGE_STD_VALUE)
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);
748 status_.convergence_status = mcl_3dl_msgs::Status::CONVERGENCE_STATUS_CONVERGED;
754 pcl::PointCloud<PointType>::Ptr pc_particle(
new pcl::PointCloud<PointType>);
755 *pc_particle = *pc_locals[
"likelihood"];
756 e.transform(*pc_particle);
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>);
769 pcl::PointCloud<PointType>::Ptr pc_local(
new pcl::PointCloud<PointType>);
770 *pc_local = *pc_local_full;
772 e.transform(*pc_local);
774 std::vector<int> id(1);
775 std::vector<float> sqdist(1);
777 for (
auto& p : pc_local->points)
781 pc_unmatch->points.emplace_back(p.x, p.y, p.z);
783 else if (sqdist[0] < match_dist_sq)
785 pc_match->points.emplace_back(p.x, p.y, p.z);
790 sensor_msgs::PointCloud2 pc2;
792 pc2.header.stamp = header.stamp;
798 sensor_msgs::PointCloud2 pc2;
800 pc2.header.stamp = header.stamp;
816 std::normal_distribution<float> noise(0.0, 1.0);
817 auto update_noise_func = [
this, &noise](
State6DOF&
s)
824 pf_->predict(update_noise_func);
826 const auto tnow = boost::chrono::high_resolution_clock::now();
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_,
846 ROS_DEBUG(
"match ratio min: %0.3f, max: %0.3f, pos: %0.3f, %0.3f, %0.3f",
862 status_.status = mcl_3dl_msgs::Status::EXPANSION_RESETTING;
876 const int reduced = pf_->getParticleSize() * 0.75;
879 pf_->resizeParticle(reduced);
891 status_.status = mcl_3dl_msgs::Status::GLOBAL_LOCALIZATION;
894 status_.match_ratio = match_ratio_max;
895 status_.particle_size = pf_->getParticleSize();
898 void cbLandmark(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg)
901 Eigen::Matrix<double, 6, 6>(
902 msg->pose.covariance.data())
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 916 const Eigen::Matrix<float, 6, 1> diff_vec =
917 (Eigen::MatrixXf(6, 1) << diff.
pos_.
x_,
925 const auto n = nd(diff_vec);
928 pf_->measure(measure_func);
940 void cbImu(
const sensor_msgs::Imu::ConstPtr& msg)
943 msg->linear_acceleration.x,
944 msg->linear_acceleration.y,
945 msg->linear_acceleration.z));
955 float dt = (msg->header.stamp -
imu_last_).toSec();
956 if (dt < 0.0 || dt > 5.0)
958 ROS_WARN(
"Detected time jump in imu. Resetting.");
967 geometry_msgs::Vector3 in, out;
968 in.x = acc_measure.
x_;
969 in.y = acc_measure.
y_;
970 in.z = acc_measure.
z_;
975 acc_measure =
Vec3(out.x, out.y, out.z);
984 axis =
Quat(trans.transform.rotation.x,
985 trans.transform.rotation.y,
986 trans.transform.rotation.z,
987 trans.transform.rotation.w) *
997 auto imu_measure_func = [
this](
const State6DOF&
s) ->
float 1001 pf_->measure(imu_measure_func);
1007 nav_msgs::Odometry::Ptr odom(
new nav_msgs::Odometry);
1009 odom->header.stamp = msg->header.stamp;
1019 mcl_3dl_msgs::ResizeParticleResponse& response)
1021 pf_->resizeParticle(request.size);
1026 std_srvs::TriggerResponse& response)
1039 std_srvs::TriggerResponse& response)
1043 response.success =
false;
1044 response.message =
"No map received.";
1047 pcl::PointCloud<PointType>::Ptr points(
new pcl::PointCloud<PointType>);
1049 pcl::VoxelGrid<PointType> ds;
1057 pcl::KdTreeFLANN<PointType>::Ptr kdtree(
new pcl::KdTreeFLANN<PointType>);
1059 kdtree->setInputCloud(points);
1061 auto pc_filter = [
this, kdtree](
const PointType& p)
1063 std::vector<int> id(1);
1064 std::vector<float> sqdist(1);
1068 return kdtree->radiusSearch(
1072 std::remove_if(points->begin(), points->end(), pc_filter),
1076 pf_->resizeParticle(points->size() * dir);
1077 auto pit = points->begin();
1079 const float prob = 1.0 /
static_cast<float>(points->size());
1081 for (
auto& particle : *pf_)
1083 assert(pit != points->end());
1084 particle.probability_ = prob;
1085 particle.probability_bias_ = 1.0;
1087 Vec3(pit->x, pit->y, pit->z),
1095 response.success =
true;
1096 response.message = std::to_string(pf_->getParticleSize()) +
" particles";
1102 geometry_msgs::PoseArray pa;
1108 for (
size_t i = 0; i < pf_->getParticleSize(); i++)
1110 geometry_msgs::Pose pm;
1111 auto p = pf_->getParticle(i);
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);
1128 for (
auto& particle : *pf_)
1130 sum += particle.probability_;
1133 float entropy = 0.0f;
1134 for (
auto& particle : *pf_)
1136 if (particle.probability_ / sum > 0.0)
1137 entropy += particle.probability_ / sum * std::log(particle.probability_ / sum);
1145 if (
status_.error == mcl_3dl_msgs::Status::ERROR_POINTS_NOT_FOUND)
1147 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Valid points does not found.");
1149 else if (
status_.convergence_status == mcl_3dl_msgs::Status::CONVERGENCE_STATUS_LARGE_STD_VALUE)
1151 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Too Large Standard Deviation.");
1155 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"OK");
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");
1168 pc_map_.reset(
new pcl::PointCloud<PointType>);
1171 pcl::VoxelGrid<PointType> ds;
1172 ds.setInputCloud(map_cloud);
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()));
1188 bool cbLoadPCD(mcl_3dl_msgs::LoadPCD::Request& req, mcl_3dl_msgs::LoadPCD::Response& resp)
1192 pcl::PointCloud<PointType>::Ptr pc_tmp(
new pcl::PointCloud<PointType>);
1193 if (pcl::io::loadPCDFile<PointType>(req.pcd_path, *pc_tmp) == -1)
1197 resp.success =
false;
1206 resp.success =
true;
1232 int odom_queue_size;
1233 pnh_.
param(
"odom_queue_size", odom_queue_size, 200);
1241 pnh_.
param(
"imu_queue_size", imu_queue_size, 200);
1247 int cloud_queue_size;
1248 pnh_.
param(
"cloud_queue_size", cloud_queue_size, 100);
1256 nh_,
"mapcloud_update",
1262 nh_,
"mcl_measurement",
1274 nh_,
"resize_mcl_particle",
1277 nh_,
"global_localization",
1280 nh_,
"expansion_resetting",
1328 float max_search_radius = 0;
1331 lm.second->loadConfig(
pnh_, lm.first);
1332 max_search_radius = std::max(max_search_radius, lm.second->getMaxSearchRange());
1336 auto sampler = std::make_shared<PointCloudSamplerWithNormal<PointType>>();
1337 sampler->loadConfig(
pnh_);
1338 lm.second->setRandomSampler(sampler);
1342 auto sampler = std::make_shared<PointCloudUniformSampler<PointType>>();
1343 lm.second->setRandomSampler(sampler);
1347 ROS_DEBUG(
"max_search_radius: %0.3f", max_search_radius);
1365 std::cerr <<
"mcl_3dl: saving pcd file.";
1366 std::cerr <<
" (" <<
pc_all_accum_->points.size() <<
" points)" << std::endl;
1375 const auto ts = boost::chrono::high_resolution_clock::now();
1379 pc_map2_.reset(
new pcl::PointCloud<PointType>);
1392 sensor_msgs::PointCloud2 out;
1395 const auto tnow = boost::chrono::high_resolution_clock::now();
1397 boost::chrono::duration<float>(tnow - ts).count());
std::default_random_engine engine_
ros::Time match_output_last_
void setAxisAng(const Vec3 &axis, const float &ang)
std::shared_ptr< pf::ParticleFilter< State6DOF, float, ParticleWeightedMeanQuat, std::default_random_engine > > pf_
bool load(ros::NodeHandle &nh)
double update_downsample_x_
void cbOdom(const nav_msgs::Odometry::ConstPtr &msg)
double resample_var_roll_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void summary(unsigned char lvl, const std::string s)
MyPointRepresentation::Ptr point_rep_
ros::Publisher pub_debug_marker_
double unmatch_output_dist_
void setHardwareID(const std::string &hwid)
ros::Subscriber sub_mapcloud_
std::shared_ptr< ChunkedKdtree > Ptr
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_
void add(const std::string &name, TaskFunction f)
std::random_device seed_gen_
bool cbLoadPCD(mcl_3dl_msgs::LoadPCD::Request &req, mcl_3dl_msgs::LoadPCD::Response &resp)
double update_downsample_z_
tf2_ros::TransformBroadcaster tfb_
double expansion_var_roll_
ros::ServiceServer srv_global_localization_
ros::Subscriber sub_cloud_
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
ros::Subscriber sub_odom_
void loadMapCloud(const pcl::PointCloud< PointType >::Ptr &map_cloud)
ros::Publisher pub_status_
pcl::PointCloud< PointType >::Ptr pc_update_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::shared_ptr< FilterVec3 > f_ang_
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_
ros::Subscriber sub_mapcloud_update_
int total_accum_cloud_max_
std::shared_ptr< Filter > localize_rate_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void getAxisAng(Vec3 &axis, float &ang) const
void publish(const boost::shared_ptr< M > &message) const
double global_localization_grid_
void cbMapUpdateTimer(const ros::TimerEvent &event)
constexpr Vec3 getRPY() const
bool accumCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
void diagnoseStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
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)
State6DOF initial_pose_std_
#define ROS_WARN_THROTTLE(period,...)
CloudAccumulationLogicBase::Ptr accum_
ros::Publisher pub_unmatched_
ros::Subscriber sub_landmark_
MotionPredictionModelBase::Ptr motion_prediction_model_
ros::Publisher pub_matched_
std::shared_ptr< LidarMeasurementModelBase > Ptr
std::array< float, 3 > std_warn_thresh_
pcl::PointCloud< PointType >::Ptr pc_local_accum_
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
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_
double expansion_var_yaw_
mcl_3dl_msgs::Status status_
std::shared_ptr< FilterVec3 > f_acc_
std::shared_ptr< FilterVec3 > f_pos_
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())
std::map< std::string, std::string > frame_ids_
void setRPY(const Vec3 &rpy)
void setParticleStatistics(const State6DOF &mean, const std::vector< State6DOF > &covariances)
std::vector< std_msgs::Header > pc_accum_header_
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
double expansion_var_pitch_
double odom_err_integ_ang_tc_
ros::Publisher pub_mapcloud_
double match_ratio_thresh_
ros::Timer map_update_timer_
void cbPosition(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
ros::Duration tf_tolerance_base_
void cbImu(const sensor_msgs::Imu::ConstPtr &msg)
void add(const std::string &key, const T &val)
ros::ServiceServer srv_load_pcd_
diagnostic_updater::Updater diag_updater_
bool use_random_sampler_with_normal_
pcl::PointCloud< PointType >::Ptr pc_map_
#define ROS_ERROR_STREAM(args)
uint32_t getNumSubscribers() const
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_
std::shared_ptr< CloudAccumulationLogicBase > Ptr
size_t global_localization_fix_cnt_
constexpr Quat inv() const
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)
std::array< float, 4 > dist_weight_