-
Notifications
You must be signed in to change notification settings - Fork 302
/
Deskew.cpp
66 lines (59 loc) · 2.94 KB
/
Deskew.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
// MIT License
//
// Copyright (c) 2022 Ignacio Vizzo, Tiziano Guadagnino, Benedikt Mersch, Cyrill
// Stachniss.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in all
// copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#include "Deskew.hpp"
#include <tbb/parallel_for.h>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <tuple>
#include <vector>
namespace {
Eigen::Isometry3d MakeTransform(const Eigen::Vector3d& xyz, const Eigen::Vector3d& rpy) {
Eigen::AngleAxisd omega(rpy.norm(), rpy.normalized());
Eigen::Isometry3d transform(omega);
transform.translation() = xyz;
return transform;
}
} // namespace
namespace kiss_icp {
std::tuple<Eigen::Vector3d, Eigen::Vector3d> VelocityEstimation(const Eigen::Matrix4d& start_pose,
const Eigen::Matrix4d& finish_pose,
double scan_duration) {
const Eigen::Matrix4d delta_pose = start_pose.inverse() * finish_pose;
const Eigen::Vector3d linear_velocity = delta_pose.block<3, 1>(0, 3) / scan_duration;
const auto angle_axis = Eigen::AngleAxisd(delta_pose.block<3, 3>(0, 0));
const Eigen::Vector3d angular_velocity = angle_axis.axis() * angle_axis.angle() / scan_duration;
return std::make_tuple(linear_velocity, angular_velocity);
}
std::vector<Eigen::Vector3d> DeSkewScan(const std::vector<Eigen::Vector3d>& frame,
const std::vector<double>& timestamps,
const Eigen::Vector3d& linear_velocity,
const Eigen::Vector3d& angular_velocity) {
std::vector<Eigen::Vector3d> corrected_frame(frame.size());
tbb::parallel_for(size_t(0), frame.size(), [&](size_t i) {
const auto& dt = timestamps[i];
const auto motion = MakeTransform(dt * linear_velocity, dt * angular_velocity);
corrected_frame[i] = motion * frame[i];
});
return corrected_frame;
}
} // namespace kiss_icp