40 #include <boost/assign.hpp> 48 nh_private_(nh_private),
51 received_odom_(
false),
54 ROS_INFO(
"Starting LaserScanMatcher");
91 "pose_with_covariance", 5);
97 "pose_with_covariance_stamped", 5);
136 ROS_INFO(
"Destroying LaserScanMatcher");
346 boost::mutex::scoped_lock(
mutex_);
357 boost::mutex::scoped_lock(
mutex_);
368 boost::mutex::scoped_lock(
mutex_);
376 boost::mutex::scoped_lock(
mutex_);
429 processScan(curr_ldp_scan, scan_msg->header.stamp);
506 meas_keyframe_base_offset = base_from_laser_ * meas_keyframe_laser_offset *
laser_from_base_;
513 Eigen::Matrix2f xy_cov = Eigen::Matrix2f::Zero();
526 xy_cov = rotation * xy_cov * rotation.transpose();
537 geometry_msgs::Pose2D::Ptr pose_msg;
538 pose_msg = boost::make_shared<geometry_msgs::Pose2D>();
547 geometry_msgs::PoseStamped::Ptr pose_stamped_msg;
548 pose_stamped_msg = boost::make_shared<geometry_msgs::PoseStamped>();
550 pose_stamped_msg->header.stamp = time;
560 geometry_msgs::PoseWithCovariance::Ptr pose_with_covariance_msg;
561 pose_with_covariance_msg = boost::make_shared<geometry_msgs::PoseWithCovariance>();
564 pose_with_covariance_msg->covariance = boost::assign::list_of
565 (xy_cov(0, 0)) (xy_cov(0, 1)) (0) (0) (0) (0)
566 (xy_cov(1, 0)) (xy_cov(1, 1)) (0) (0) (0) (0)
567 (0) (0) (0) (0) (0) (0)
568 (0) (0) (0) (0) (0) (0)
569 (0) (0) (0) (0) (0) (0)
570 (0) (0) (0) (0) (0) (yaw_cov);
577 geometry_msgs::PoseWithCovarianceStamped::Ptr pose_with_covariance_stamped_msg;
578 pose_with_covariance_stamped_msg = boost::make_shared<geometry_msgs::PoseWithCovarianceStamped>();
580 pose_with_covariance_stamped_msg->header.stamp = time;
581 pose_with_covariance_stamped_msg->header.frame_id =
fixed_frame_;
585 pose_with_covariance_stamped_msg->pose.covariance = boost::assign::list_of
586 (xy_cov(0, 0)) (xy_cov(0, 1)) (0) (0) (0) (0)
587 (xy_cov(1, 0)) (xy_cov(1, 1)) (0) (0) (0) (0)
588 (0) (0) (0) (0) (0) (0)
589 (0) (0) (0) (0) (0) (0)
590 (0) (0) (0) (0) (0) (0)
591 (0) (0) (0) (0) (0) (yaw_cov);
627 ROS_DEBUG(
"Scan matcher total duration: %.1f ms", dur);
648 cloud_f.points.push_back(cloud->points[0]);
650 for (
unsigned int i = 1; i < cloud->points.size(); ++i)
652 const PointT& pa = cloud_f.points[cloud_f.points.size() - 1];
653 const PointT& pb = cloud->points[i];
655 double dx = pa.x - pb.x;
656 double dy = pa.y - pb.y;
657 double d2 = dx*dx + dy*dy;
661 cloud_f.points.push_back(pb);
665 unsigned int n = cloud_f.points.size();
669 for (
unsigned int i = 0; i < n; i++)
672 if (
is_nan(cloud_f.points[i].x) ||
is_nan(cloud_f.points[i].y))
674 ROS_WARN(
"Laser Scan Matcher: Cloud input contains NaN values. \ 675 Please use a filtered cloud input.");
679 double r = sqrt(cloud_f.points[i].x * cloud_f.points[i].x +
680 cloud_f.points[i].y * cloud_f.points[i].y);
694 ldp->
theta[i] = atan2(cloud_f.points[i].y, cloud_f.points[i].x);
713 unsigned int n = scan_msg->ranges.size();
716 for (
unsigned int i = 0; i < n; i++)
720 double r = scan_msg->ranges[i];
722 if (r > scan_msg->range_min && r < scan_msg->range_max)
735 ldp->
theta[i] = scan_msg->angle_min + i * scan_msg->angle_increment;
757 for (
unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
759 double angle = scan_msg->angle_min + i * scan_msg->angle_increment;
760 a_cos_.push_back(cos(angle));
761 a_sin_.push_back(sin(angle));
778 ROS_WARN(
"Could not get initial transform from base to laser frame, %s", ex.what());
790 boost::mutex::scoped_lock(
mutex_);
828 pred_last_base_offset.
setRotation(imu_orientation_offset);
841 pred_last_base_offset = pred_last_base_offset_tf;
845 ROS_WARN(
"Could not get base to fixed frame transform, %s", ex.what());
849 return pred_last_base_offset;
857 q.
setRPY(0.0, 0.0, theta);
865 fixed_from_laser_rot.getRPY(r, p, y);
866 Eigen::Rotation2Df t(y);
867 return t.toRotationMatrix();
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
Quaternion inverse() const
void sm_icp(struct sm_params *input, struct sm_result *output)
int outliers_remove_doubles
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static double getYaw(const Quaternion &bt_q)
double max_angular_correction_deg
int orientation_neighbourhood
double clustering_threshold
double max_linear_correction
double outliers_adaptive_mult
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double restart_threshold_mean_error
double *restrict readings
double max_correspondence_dist
void publish(const boost::shared_ptr< M > &message) const
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
bool getParam(const std::string &key, std::string &s) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double do_alpha_test_thresholdDeg
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
int do_compute_covariance
double outliers_adaptive_order
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
LDP ld_alloc_new(int nrays)
int use_point_to_line_distance