-
Notifications
You must be signed in to change notification settings - Fork 956
/
ScanRegistration.cpp
201 lines (170 loc) · 7.33 KB
/
ScanRegistration.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
// Copyright 2013, Ji Zhang, Carnegie Mellon University
// Further contributions copyright (c) 2016, Southwest Research Institute
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
// 3. Neither the name of the copyright holder nor the names of its
// contributors may be used to endorse or promote products derived from this
// software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// This is an implementation of the algorithm described in the following paper:
// J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time.
// Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014.
#include "loam_velodyne/ScanRegistration.h"
#include "math_utils.h"
#include <tf/transform_datatypes.h>
namespace loam {
bool ScanRegistration::parseParams(const ros::NodeHandle& nh, RegistrationParams& config_out)
{
bool success = true;
int iParam = 0;
float fParam = 0;
if (nh.getParam("scanPeriod", fParam)) {
if (fParam <= 0) {
ROS_ERROR("Invalid scanPeriod parameter: %f (expected > 0)", fParam);
success = false;
} else {
config_out.scanPeriod = fParam;
ROS_INFO("Set scanPeriod: %g", fParam);
}
}
if (nh.getParam("imuHistorySize", iParam)) {
if (iParam < 1) {
ROS_ERROR("Invalid imuHistorySize parameter: %d (expected >= 1)", iParam);
success = false;
} else {
config_out.imuHistorySize = iParam;
ROS_INFO("Set imuHistorySize: %d", iParam);
}
}
if (nh.getParam("featureRegions", iParam)) {
if (iParam < 1) {
ROS_ERROR("Invalid featureRegions parameter: %d (expected >= 1)", iParam);
success = false;
} else {
config_out.nFeatureRegions = iParam;
ROS_INFO("Set nFeatureRegions: %d", iParam);
}
}
if (nh.getParam("curvatureRegion", iParam)) {
if (iParam < 1) {
ROS_ERROR("Invalid curvatureRegion parameter: %d (expected >= 1)", iParam);
success = false;
} else {
config_out.curvatureRegion = iParam;
ROS_INFO("Set curvatureRegion: +/- %d", iParam);
}
}
if (nh.getParam("maxCornerSharp", iParam)) {
if (iParam < 1) {
ROS_ERROR("Invalid maxCornerSharp parameter: %d (expected >= 1)", iParam);
success = false;
} else {
config_out.maxCornerSharp = iParam;
config_out.maxCornerLessSharp = 10 * iParam;
ROS_INFO("Set maxCornerSharp / less sharp: %d / %d", iParam, config_out.maxCornerLessSharp);
}
}
if (nh.getParam("maxCornerLessSharp", iParam)) {
if (iParam < config_out.maxCornerSharp) {
ROS_ERROR("Invalid maxCornerLessSharp parameter: %d (expected >= %d)", iParam, config_out.maxCornerSharp);
success = false;
} else {
config_out.maxCornerLessSharp = iParam;
ROS_INFO("Set maxCornerLessSharp: %d", iParam);
}
}
if (nh.getParam("maxSurfaceFlat", iParam)) {
if (iParam < 1) {
ROS_ERROR("Invalid maxSurfaceFlat parameter: %d (expected >= 1)", iParam);
success = false;
} else {
config_out.maxSurfaceFlat = iParam;
ROS_INFO("Set maxSurfaceFlat: %d", iParam);
}
}
if (nh.getParam("surfaceCurvatureThreshold", fParam)) {
if (fParam < 0.001) {
ROS_ERROR("Invalid surfaceCurvatureThreshold parameter: %f (expected >= 0.001)", fParam);
success = false;
} else {
config_out.surfaceCurvatureThreshold = fParam;
ROS_INFO("Set surfaceCurvatureThreshold: %g", fParam);
}
}
if (nh.getParam("lessFlatFilterSize", fParam)) {
if (fParam < 0.001) {
ROS_ERROR("Invalid lessFlatFilterSize parameter: %f (expected >= 0.001)", fParam);
success = false;
} else {
config_out.lessFlatFilterSize = fParam;
ROS_INFO("Set lessFlatFilterSize: %g", fParam);
}
}
return success;
}
bool ScanRegistration::setupROS(ros::NodeHandle& node, ros::NodeHandle& privateNode, RegistrationParams& config_out)
{
if (!parseParams(privateNode, config_out))
return false;
// subscribe to IMU topic
_subImu = node.subscribe<sensor_msgs::Imu>("/imu/data", 50, &ScanRegistration::handleIMUMessage, this);
// advertise scan registration topics
_pubLaserCloud = node.advertise<sensor_msgs::PointCloud2>("/velodyne_cloud_2", 2);
_pubCornerPointsSharp = node.advertise<sensor_msgs::PointCloud2>("/laser_cloud_sharp", 2);
_pubCornerPointsLessSharp = node.advertise<sensor_msgs::PointCloud2>("/laser_cloud_less_sharp", 2);
_pubSurfPointsFlat = node.advertise<sensor_msgs::PointCloud2>("/laser_cloud_flat", 2);
_pubSurfPointsLessFlat = node.advertise<sensor_msgs::PointCloud2>("/laser_cloud_less_flat", 2);
_pubImuTrans = node.advertise<sensor_msgs::PointCloud2>("/imu_trans", 5);
return true;
}
void ScanRegistration::handleIMUMessage(const sensor_msgs::Imu::ConstPtr& imuIn)
{
tf::Quaternion orientation;
tf::quaternionMsgToTF(imuIn->orientation, orientation);
double roll, pitch, yaw;
tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
Vector3 acc;
acc.x() = float(imuIn->linear_acceleration.y - sin(roll) * cos(pitch) * 9.81);
acc.y() = float(imuIn->linear_acceleration.z - cos(roll) * cos(pitch) * 9.81);
acc.z() = float(imuIn->linear_acceleration.x + sin(pitch) * 9.81);
IMUState newState;
newState.stamp = fromROSTime( imuIn->header.stamp);
newState.roll = roll;
newState.pitch = pitch;
newState.yaw = yaw;
newState.acceleration = acc;
updateIMUData(acc, newState);
}
void ScanRegistration::publishResult()
{
auto sweepStartTime = toROSTime(sweepStart());
// publish full resolution and feature point clouds
publishCloudMsg(_pubLaserCloud, laserCloud(), sweepStartTime, "/camera");
publishCloudMsg(_pubCornerPointsSharp, cornerPointsSharp(), sweepStartTime, "/camera");
publishCloudMsg(_pubCornerPointsLessSharp, cornerPointsLessSharp(), sweepStartTime, "/camera");
publishCloudMsg(_pubSurfPointsFlat, surfacePointsFlat(), sweepStartTime, "/camera");
publishCloudMsg(_pubSurfPointsLessFlat, surfacePointsLessFlat(), sweepStartTime, "/camera");
// publish corresponding IMU transformation information
publishCloudMsg(_pubImuTrans, imuTransform(), sweepStartTime, "/camera");
}
} // end namespace loam