laser_scan_matcher.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Ivan Dryanovski, William Morris
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 CCNY Robotics Lab 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 /* This package uses Canonical Scan Matcher [1], written by
31  * Andrea Censi
32  *
33  * [1] A. Censi, "An ICP variant using a point-to-line metric"
34  * Proceedings of the IEEE International Conference
35  * on Robotics and Automation (ICRA), 2008
36  */
37 
38 #ifndef LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
39 #define LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
40 
41 #include <ros/ros.h>
42 #include <sensor_msgs/Imu.h>
43 #include <sensor_msgs/LaserScan.h>
44 #include <geometry_msgs/PoseStamped.h>
45 #include <geometry_msgs/Pose2D.h>
46 #include <geometry_msgs/PoseWithCovarianceStamped.h>
47 #include <geometry_msgs/PoseWithCovariance.h>
48 #include <geometry_msgs/TwistStamped.h>
49 #include <nav_msgs/Odometry.h>
50 #include <tf/transform_datatypes.h>
51 #include <tf/transform_listener.h>
53 #include <pcl/point_types.h>
54 #include <pcl/point_cloud.h>
55 #include <pcl/filters/voxel_grid.h>
56 #include <pcl_ros/point_cloud.h>
57 
58 #include <csm/csm_all.h> // csm defines min and max, but Eigen complains
59 #undef min
60 #undef max
61 
62 namespace scan_tools
63 {
64 
66 {
67  public:
68 
71 
72  private:
73 
74  typedef pcl::PointXYZ PointT;
75  typedef pcl::PointCloud<PointT> PointCloudT;
76 
77  // **** ros
78 
81 
87 
90 
91  tf::Transform base_from_laser_; // static, cached
92  tf::Transform laser_from_base_; // static, cached
93 
98 
99  // **** parameters
100 
101  std::string base_frame_;
102  std::string fixed_frame_;
105  double cloud_res_;
111  std::vector<double> position_covariance_;
112  std::vector<double> orientation_covariance_;
113 
115 
119 
120  // **** What predictions are available to speed up the ICP?
121  // 1) imu - [theta] from imu yaw angle - /imu topic
122  // 2) odom - [x, y, theta] from wheel odometry - /odom topic
123  // 3) tf - [x, y, theta] from /tf topic
124  // 3) velocity [vx, vy, vtheta], usually from ab-filter - /vel.
125  // If more than one is enabled, priority is tf > imu > odom > velocity
126 
127  bool use_imu_;
128  bool use_odom_;
129  bool use_tf_;
130  double tf_timeout_;
131  bool use_vel_;
133 
134  // **** state variables
135 
136  boost::mutex mutex_;
137 
142 
143  tf::Transform last_base_in_fixed_; // pose of the base of the last scan in fixed frame
144  tf::Transform keyframe_base_in_fixed_; // pose of the base of last keyframe scan in fixed frame
145 
147 
148  sensor_msgs::Imu latest_imu_msg_;
150  nav_msgs::Odometry latest_odom_msg_;
152 
153  geometry_msgs::Twist latest_vel_msg_;
154 
155  std::vector<double> a_cos_;
156  std::vector<double> a_sin_;
157 
161 
162  // **** methods
163 
164  void initParams();
165  void processScan(LDP& curr_ldp_scan, const ros::Time& time);
166 
167  void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
168  LDP& ldp);
169  void PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
170  LDP& ldp);
171 
172  void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
173  void cloudCallback (const PointCloudT::ConstPtr& cloud);
174 
175  void odomCallback(const nav_msgs::Odometry::ConstPtr& odom_msg);
176  void imuCallback (const sensor_msgs::Imu::ConstPtr& imu_msg);
177  void velCallback (const geometry_msgs::Twist::ConstPtr& twist_msg);
178  void velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr& twist_msg);
179 
180  void createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
181 
189  bool getBaseLaserTransform(const std::string& frame_id);
190 
191  bool newKeyframeNeeded(const tf::Transform& d);
192 
193  tf::Transform getPrediction(const ros::Time& stamp);
194 
195  void createTfFromXYTheta(double x, double y, double theta, tf::Transform& t);
196 
197  Eigen::Matrix2f getLaserRotation(const tf::Transform& odom_pose) const;
198 };
199 
200 } // namespace scan_tools
201 
202 #endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
scan_tools::LaserScanMatcher::processScan
void processScan(LDP &curr_ldp_scan, const ros::Time &time)
Definition: laser_scan_matcher.cpp:432
ros::Publisher
scan_tools::LaserScanMatcher::PointCloudToLDP
void PointCloudToLDP(const PointCloudT::ConstPtr &cloud, LDP &ldp)
Definition: laser_scan_matcher.cpp:641
scan_tools::LaserScanMatcher::kf_dist_angular_
double kf_dist_angular_
Definition: laser_scan_matcher.h:118
scan_tools::LaserScanMatcher::use_cloud_input_
bool use_cloud_input_
Definition: laser_scan_matcher.h:114
scan_tools::LaserScanMatcher::imu_subscriber_
ros::Subscriber imu_subscriber_
Definition: laser_scan_matcher.h:85
scan_tools::LaserScanMatcher::tf_timeout_
double tf_timeout_
Definition: laser_scan_matcher.h:130
scan_tools::LaserScanMatcher::tf_listener_
tf::TransformListener tf_listener_
Definition: laser_scan_matcher.h:88
scan_tools::LaserScanMatcher::last_base_in_fixed_
tf::Transform last_base_in_fixed_
Definition: laser_scan_matcher.h:143
ros.h
scan_tools::LaserScanMatcher::a_sin_
std::vector< double > a_sin_
Definition: laser_scan_matcher.h:156
scan_tools::LaserScanMatcher::laserScanToLDP
void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr &scan_msg, LDP &ldp)
Definition: laser_scan_matcher.cpp:710
scan_tools::LaserScanMatcher::prev_ldp_scan_
LDP prev_ldp_scan_
Definition: laser_scan_matcher.h:160
scan_tools::LaserScanMatcher::cloud_res_
double cloud_res_
Definition: laser_scan_matcher.h:105
scan_tools::LaserScanMatcher::nh_private_
ros::NodeHandle nh_private_
Definition: laser_scan_matcher.h:80
scan_tools::LaserScanMatcher::publish_pose_stamped_
bool publish_pose_stamped_
Definition: laser_scan_matcher.h:109
sm_params
scan_tools::LaserScanMatcher::last_used_imu_orientation_
tf::Quaternion last_used_imu_orientation_
Definition: laser_scan_matcher.h:149
scan_tools::LaserScanMatcher::tf_broadcaster_
tf::TransformBroadcaster tf_broadcaster_
Definition: laser_scan_matcher.h:89
scan_tools::LaserScanMatcher::stamped_vel_
bool stamped_vel_
Definition: laser_scan_matcher.h:132
scan_tools::LaserScanMatcher::publish_pose_with_covariance_
bool publish_pose_with_covariance_
Definition: laser_scan_matcher.h:108
scan_tools::LaserScanMatcher::scanCallback
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
Definition: laser_scan_matcher.cpp:407
scan_tools::LaserScanMatcher::mutex_
boost::mutex mutex_
Definition: laser_scan_matcher.h:136
scan_tools::LaserScanMatcher::output_
sm_result output_
Definition: laser_scan_matcher.h:159
scan_tools::LaserScanMatcher::scan_subscriber_
ros::Subscriber scan_subscriber_
Definition: laser_scan_matcher.h:82
scan_tools::LaserScanMatcher::cloud_range_max_
double cloud_range_max_
Definition: laser_scan_matcher.h:104
transform_broadcaster.h
point_cloud.h
scan_tools::LaserScanMatcher::laser_from_base_
tf::Transform laser_from_base_
Definition: laser_scan_matcher.h:92
scan_tools::LaserScanMatcher::use_imu_
bool use_imu_
Definition: laser_scan_matcher.h:127
scan_tools::LaserScanMatcher::orientation_covariance_
std::vector< double > orientation_covariance_
Definition: laser_scan_matcher.h:112
scan_tools::LaserScanMatcher::publish_tf_
bool publish_tf_
Definition: laser_scan_matcher.h:106
scan_tools
Definition: laser_scan_matcher.h:62
scan_tools::LaserScanMatcher::a_cos_
std::vector< double > a_cos_
Definition: laser_scan_matcher.h:155
tf::TransformBroadcaster
scan_tools::LaserScanMatcher::getBaseLaserTransform
bool getBaseLaserTransform(const std::string &frame_id)
Definition: laser_scan_matcher.cpp:768
scan_tools::LaserScanMatcher::cloud_subscriber_
ros::Subscriber cloud_subscriber_
Definition: laser_scan_matcher.h:83
scan_tools::LaserScanMatcher::latest_vel_msg_
geometry_msgs::Twist latest_vel_msg_
Definition: laser_scan_matcher.h:153
scan_tools::LaserScanMatcher::odom_subscriber_
ros::Subscriber odom_subscriber_
Definition: laser_scan_matcher.h:84
scan_tools::LaserScanMatcher::use_odom_
bool use_odom_
Definition: laser_scan_matcher.h:128
scan_tools::LaserScanMatcher::received_vel_
bool received_vel_
Definition: laser_scan_matcher.h:141
scan_tools::LaserScanMatcher::vel_subscriber_
ros::Subscriber vel_subscriber_
Definition: laser_scan_matcher.h:86
scan_tools::LaserScanMatcher::last_used_odom_pose_
tf::Transform last_used_odom_pose_
Definition: laser_scan_matcher.h:151
scan_tools::LaserScanMatcher::cloud_range_min_
double cloud_range_min_
Definition: laser_scan_matcher.h:103
scan_tools::LaserScanMatcher::newKeyframeNeeded
bool newKeyframeNeeded(const tf::Transform &d)
Definition: laser_scan_matcher.cpp:630
scan_tools::LaserScanMatcher::getLaserRotation
Eigen::Matrix2f getLaserRotation(const tf::Transform &odom_pose) const
Definition: laser_scan_matcher.cpp:861
scan_tools::LaserScanMatcher::PointT
pcl::PointXYZ PointT
Definition: laser_scan_matcher.h:74
scan_tools::LaserScanMatcher::position_covariance_
std::vector< double > position_covariance_
Definition: laser_scan_matcher.h:111
scan_tools::LaserScanMatcher::createCache
void createCache(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
Definition: laser_scan_matcher.cpp:752
tf::Transform
scan_tools::LaserScanMatcher::LaserScanMatcher
LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private)
Definition: laser_scan_matcher.cpp:46
scan_tools::LaserScanMatcher::nh_
ros::NodeHandle nh_
Definition: laser_scan_matcher.h:79
scan_tools::LaserScanMatcher::received_imu_
bool received_imu_
Definition: laser_scan_matcher.h:139
scan_tools::LaserScanMatcher::initParams
void initParams()
Definition: laser_scan_matcher.cpp:139
transform_listener.h
scan_tools::LaserScanMatcher::odomCallback
void odomCallback(const nav_msgs::Odometry::ConstPtr &odom_msg)
Definition: laser_scan_matcher.cpp:355
scan_tools::LaserScanMatcher::getPrediction
tf::Transform getPrediction(const ros::Time &stamp)
Definition: laser_scan_matcher.cpp:788
scan_tools::LaserScanMatcher::imuCallback
void imuCallback(const sensor_msgs::Imu::ConstPtr &imu_msg)
Definition: laser_scan_matcher.cpp:344
scan_tools::LaserScanMatcher::velCallback
void velCallback(const geometry_msgs::Twist::ConstPtr &twist_msg)
Definition: laser_scan_matcher.cpp:366
scan_tools::LaserScanMatcher::cloudCallback
void cloudCallback(const PointCloudT::ConstPtr &cloud)
Definition: laser_scan_matcher.cpp:382
scan_tools::LaserScanMatcher::kf_dist_linear_sq_
double kf_dist_linear_sq_
Definition: laser_scan_matcher.h:117
scan_tools::LaserScanMatcher::publish_pose_with_covariance_stamped_
bool publish_pose_with_covariance_stamped_
Definition: laser_scan_matcher.h:110
scan_tools::LaserScanMatcher::fixed_frame_
std::string fixed_frame_
Definition: laser_scan_matcher.h:102
transform_datatypes.h
scan_tools::LaserScanMatcher::received_odom_
bool received_odom_
Definition: laser_scan_matcher.h:140
ros::Time
sm_result
scan_tools::LaserScanMatcher::use_tf_
bool use_tf_
Definition: laser_scan_matcher.h:129
scan_tools::LaserScanMatcher::keyframe_base_in_fixed_
tf::Transform keyframe_base_in_fixed_
Definition: laser_scan_matcher.h:144
scan_tools::LaserScanMatcher
Definition: laser_scan_matcher.h:65
tf::TransformListener
scan_tools::LaserScanMatcher::pose_publisher_
ros::Publisher pose_publisher_
Definition: laser_scan_matcher.h:94
laser_data
scan_tools::LaserScanMatcher::pose_stamped_publisher_
ros::Publisher pose_stamped_publisher_
Definition: laser_scan_matcher.h:95
scan_tools::LaserScanMatcher::last_icp_time_
ros::Time last_icp_time_
Definition: laser_scan_matcher.h:146
scan_tools::LaserScanMatcher::latest_imu_msg_
sensor_msgs::Imu latest_imu_msg_
Definition: laser_scan_matcher.h:148
scan_tools::LaserScanMatcher::pose_with_covariance_stamped_publisher_
ros::Publisher pose_with_covariance_stamped_publisher_
Definition: laser_scan_matcher.h:97
scan_tools::LaserScanMatcher::latest_odom_msg_
nav_msgs::Odometry latest_odom_msg_
Definition: laser_scan_matcher.h:150
scan_tools::LaserScanMatcher::base_from_laser_
tf::Transform base_from_laser_
Definition: laser_scan_matcher.h:91
scan_tools::LaserScanMatcher::createTfFromXYTheta
void createTfFromXYTheta(double x, double y, double theta, tf::Transform &t)
Definition: laser_scan_matcher.cpp:852
scan_tools::LaserScanMatcher::~LaserScanMatcher
~LaserScanMatcher()
Definition: laser_scan_matcher.cpp:134
scan_tools::LaserScanMatcher::base_frame_
std::string base_frame_
Definition: laser_scan_matcher.h:101
scan_tools::LaserScanMatcher::use_vel_
bool use_vel_
Definition: laser_scan_matcher.h:131
scan_tools::LaserScanMatcher::input_
sm_params input_
Definition: laser_scan_matcher.h:158
scan_tools::LaserScanMatcher::pose_with_covariance_publisher_
ros::Publisher pose_with_covariance_publisher_
Definition: laser_scan_matcher.h:96
tf::Quaternion
csm_all.h
scan_tools::LaserScanMatcher::initialized_
bool initialized_
Definition: laser_scan_matcher.h:138
scan_tools::LaserScanMatcher::kf_dist_linear_
double kf_dist_linear_
Definition: laser_scan_matcher.h:116
scan_tools::LaserScanMatcher::publish_pose_
bool publish_pose_
Definition: laser_scan_matcher.h:107
ros::NodeHandle
ros::Subscriber
scan_tools::LaserScanMatcher::velStmpCallback
void velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr &twist_msg)
Definition: laser_scan_matcher.cpp:374
scan_tools::LaserScanMatcher::PointCloudT
pcl::PointCloud< PointT > PointCloudT
Definition: laser_scan_matcher.h:75


laser_scan_matcher
Author(s): Ivan Dryanovski , William Morris, Andrea Censi
autogenerated on Thu Oct 19 2023 02:48:35