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_to_laser_; // static, cached
92  tf::Transform laser_to_base_; // static, cached, calculated from base_to_laser_
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) velocity [vx, vy, vtheta], usually from ab-filter - /vel.
124  // If more than one is enabled, priority is imu > odom > velocity
125 
126  bool use_imu_;
127  bool use_odom_;
128  bool use_vel_;
130 
131  // **** state variables
132 
133  boost::mutex mutex_;
134 
139 
140  tf::Transform f2b_; // fixed-to-base tf (pose of base frame in fixed frame)
141  tf::Transform f2b_kf_; // pose of the last keyframe scan in fixed frame
142 
144 
145  sensor_msgs::Imu latest_imu_msg_;
146  sensor_msgs::Imu last_used_imu_msg_;
147  nav_msgs::Odometry latest_odom_msg_;
148  nav_msgs::Odometry last_used_odom_msg_;
149 
150  geometry_msgs::Twist latest_vel_msg_;
151 
152  std::vector<double> a_cos_;
153  std::vector<double> a_sin_;
154 
158 
159  // **** methods
160 
161  void initParams();
162  void processScan(LDP& curr_ldp_scan, const ros::Time& time);
163 
164  void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
165  LDP& ldp);
166  void PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
167  LDP& ldp);
168 
169  void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
170  void cloudCallback (const PointCloudT::ConstPtr& cloud);
171 
172  void odomCallback(const nav_msgs::Odometry::ConstPtr& odom_msg);
173  void imuCallback (const sensor_msgs::Imu::ConstPtr& imu_msg);
174  void velCallback (const geometry_msgs::Twist::ConstPtr& twist_msg);
175  void velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr& twist_msg);
176 
177  void createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
178  bool getBaseToLaserTf (const std::string& frame_id);
179 
180  bool newKeyframeNeeded(const tf::Transform& d);
181 
182  void getPrediction(double& pr_ch_x, double& pr_ch_y,
183  double& pr_ch_a, double dt);
184 
185  void createTfFromXYTheta(double x, double y, double theta, tf::Transform& t);
186 };
187 
188 } // namespace scan_tools
189 
190 #endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
void velCallback(const geometry_msgs::Twist::ConstPtr &twist_msg)
void PointCloudToLDP(const PointCloudT::ConstPtr &cloud, LDP &ldp)
pcl::PointCloud< PointT > PointCloudT
std::vector< double > position_covariance_
ros::Publisher pose_with_covariance_stamped_publisher_
ros::Publisher pose_with_covariance_publisher_
void imuCallback(const sensor_msgs::Imu::ConstPtr &imu_msg)
void odomCallback(const nav_msgs::Odometry::ConstPtr &odom_msg)
void cloudCallback(const PointCloudT::ConstPtr &cloud)
void createCache(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
std::vector< double > a_sin_
nav_msgs::Odometry last_used_odom_msg_
LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private)
void processScan(LDP &curr_ldp_scan, const ros::Time &time)
void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr &scan_msg, LDP &ldp)
void createTfFromXYTheta(double x, double y, double theta, tf::Transform &t)
nav_msgs::Odometry latest_odom_msg_
std::vector< double > orientation_covariance_
void velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr &twist_msg)
tf::TransformBroadcaster tf_broadcaster_
std::vector< double > a_cos_
geometry_msgs::Twist latest_vel_msg_
void getPrediction(double &pr_ch_x, double &pr_ch_y, double &pr_ch_a, double dt)
bool getBaseToLaserTf(const std::string &frame_id)
bool newKeyframeNeeded(const tf::Transform &d)
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
tf::TransformListener tf_listener_


laser_scan_matcher
Author(s): Ivan Dryanovski , William Morris, Andrea Censi
autogenerated on Mon Jun 10 2019 15:08:40