Apollo 10.0
自动驾驶开放平台
compensator.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
18
19#include <limits>
20#include <memory>
21#include <string>
22
23namespace apollo {
24namespace drivers {
25namespace velodyne {
26
27bool Compensator::QueryPoseAffineFromTF2(const uint64_t& timestamp, void* pose,
28 const std::string& child_frame_id) {
29 cyber::Time query_time(timestamp);
30 std::string err_string;
31 if (!tf2_buffer_ptr_->canTransform(
32 config_.world_frame_id(), child_frame_id, query_time,
33 config_.transform_query_timeout(), &err_string)) {
34 AERROR << "Can not find transform. " << timestamp
35 << " frame_id:" << child_frame_id << " Error info: " << err_string;
36 return false;
37 }
38
40
41 try {
42 stamped_transform = tf2_buffer_ptr_->lookupTransform(
43 config_.world_frame_id(), child_frame_id, query_time);
44 } catch (tf2::TransformException& ex) {
45 AERROR << ex.what();
46 return false;
47 }
48
49 Eigen::Affine3d* tmp_pose = (Eigen::Affine3d*)pose;
50 *tmp_pose =
51 Eigen::Translation3d(stamped_transform.transform().translation().x(),
52 stamped_transform.transform().translation().y(),
53 stamped_transform.transform().translation().z()) *
54 Eigen::Quaterniond(stamped_transform.transform().rotation().qw(),
55 stamped_transform.transform().rotation().qx(),
56 stamped_transform.transform().rotation().qy(),
57 stamped_transform.transform().rotation().qz());
58 return true;
59}
60
62 const std::shared_ptr<const PointCloud>& msg,
63 std::shared_ptr<PointCloud> msg_compensated) {
64 if (msg->height() == 0 || msg->width() == 0) {
65 AERROR << "PointCloud width & height should not be 0";
66 return false;
67 }
68 uint64_t start = cyber::Time::Now().ToNanosecond();
69 Eigen::Affine3d pose_min_time;
70 Eigen::Affine3d pose_max_time;
71
72 uint64_t timestamp_min = 0;
73 uint64_t timestamp_max = 0;
74 std::string frame_id = msg->header().frame_id();
75 GetTimestampInterval(msg, &timestamp_min, &timestamp_max);
76
77 msg_compensated->mutable_header()->set_timestamp_sec(
78 cyber::Time::Now().ToSecond());
79 msg_compensated->mutable_header()->set_frame_id(msg->header().frame_id());
80 msg_compensated->mutable_header()->set_lidar_timestamp(
81 msg->header().lidar_timestamp());
82 msg_compensated->set_measurement_time(msg->measurement_time());
83 msg_compensated->set_height(msg->height());
84 msg_compensated->set_is_dense(msg->is_dense());
85
86 uint64_t new_time = cyber::Time().Now().ToNanosecond();
87 AINFO << "compenstator new msg diff:" << new_time - start
88 << ";meta:" << msg->header().lidar_timestamp();
89 msg_compensated->mutable_point()->Reserve(240000);
90
91 // compensate point cloud, remove nan point
92 if (QueryPoseAffineFromTF2(timestamp_min, &pose_min_time, frame_id) &&
93 QueryPoseAffineFromTF2(timestamp_max, &pose_max_time, frame_id)) {
94 uint64_t tf_time = cyber::Time().Now().ToNanosecond();
95 AINFO << "compenstator tf msg diff:" << tf_time - new_time
96 << ";meta:" << msg->header().lidar_timestamp();
97 MotionCompensation(msg, msg_compensated, timestamp_min, timestamp_max,
98 pose_min_time, pose_max_time);
99 uint64_t com_time = cyber::Time().Now().ToNanosecond();
100 msg_compensated->set_width(msg_compensated->point_size() / msg->height());
101 AINFO << "compenstator com msg diff:" << com_time - tf_time
102 << ";meta:" << msg->header().lidar_timestamp();
103 return true;
104 }
105 return false;
106}
107
108inline void Compensator::GetTimestampInterval(
109 const std::shared_ptr<const PointCloud>& msg, uint64_t* timestamp_min,
110 uint64_t* timestamp_max) {
111 *timestamp_max = 0;
112 *timestamp_min = std::numeric_limits<uint64_t>::max();
113
114 for (const auto& point : msg->point()) {
115 uint64_t timestamp = point.timestamp();
116 if (timestamp < *timestamp_min) {
117 *timestamp_min = timestamp;
118 }
119
120 if (timestamp > *timestamp_max) {
121 *timestamp_max = timestamp;
122 }
123 }
124}
125
127 const std::shared_ptr<const PointCloud>& msg,
128 std::shared_ptr<PointCloud> msg_compensated, const uint64_t timestamp_min,
129 const uint64_t timestamp_max, const Eigen::Affine3d& pose_min_time,
130 const Eigen::Affine3d& pose_max_time) {
131 using std::abs;
132 using std::acos;
133 using std::sin;
134
135 Eigen::Vector3d translation =
136 pose_min_time.translation() - pose_max_time.translation();
137 Eigen::Quaterniond q_max(pose_max_time.linear());
138 Eigen::Quaterniond q_min(pose_min_time.linear());
139 Eigen::Quaterniond q1(q_max.conjugate() * q_min);
140 Eigen::Quaterniond q0(Eigen::Quaterniond::Identity());
141 q1.normalize();
142 translation = q_max.conjugate() * translation;
143
144 // int total = msg->width * msg->height;
145
146 double d = q0.dot(q1);
147 double abs_d = abs(d);
148 double f = 1.0 / static_cast<double>(timestamp_max - timestamp_min);
149
150 // Threshold for a "significant" rotation from min_time to max_time:
151 // The LiDAR range accuracy is ~2 cm. Over 70 meters range, it means an angle
152 // of 0.02 / 70 =
153 // 0.0003 rad. So, we consider a rotation "significant" only if the scalar
154 // part of quaternion is
155 // less than cos(0.0003 / 2) = 1 - 1e-8.
156 if (abs_d < 1.0 - 1.0e-8) {
157 double theta = acos(abs_d);
158 double sin_theta = sin(theta);
159 double c1_sign = (d > 0) ? 1 : -1;
160 for (const auto& point : msg->point()) {
161 float x_scalar = point.x();
162 if (std::isnan(x_scalar)) {
163 // if (config_.organized()) {
164 auto* point_new = msg_compensated->add_point();
165 point_new->CopyFrom(point);
166 // } else {
167 // AERROR << "nan point do not need motion compensation";
168 // }
169 continue;
170 }
171 float y_scalar = point.y();
172 float z_scalar = point.z();
173 Eigen::Vector3d p(x_scalar, y_scalar, z_scalar);
174
175 uint64_t tp = point.timestamp();
176 double t = static_cast<double>(timestamp_max - tp) * f;
177
178 Eigen::Translation3d ti(t * translation);
179
180 double c0 = sin((1 - t) * theta) / sin_theta;
181 double c1 = sin(t * theta) / sin_theta * c1_sign;
182 Eigen::Quaterniond qi(c0 * q0.coeffs() + c1 * q1.coeffs());
183
184 Eigen::Affine3d trans = ti * qi;
185 p = trans * p;
186
187 auto* point_new = msg_compensated->add_point();
188 point_new->set_intensity(point.intensity());
189 point_new->set_timestamp(point.timestamp());
190 point_new->set_x(static_cast<float>(p.x()));
191 point_new->set_y(static_cast<float>(p.y()));
192 point_new->set_z(static_cast<float>(p.z()));
193 }
194 return;
195 }
196 // Not a "significant" rotation. Do translation only.
197 for (auto& point : msg->point()) {
198 float x_scalar = point.x();
199 if (std::isnan(x_scalar)) {
200 // AERROR << "nan point do not need motion compensation";
201 continue;
202 }
203 float y_scalar = point.y();
204 float z_scalar = point.z();
205 Eigen::Vector3d p(x_scalar, y_scalar, z_scalar);
206
207 uint64_t tp = point.timestamp();
208 double t = static_cast<double>(timestamp_max - tp) * f;
209 Eigen::Translation3d ti(t * translation);
210
211 p = ti * p;
212
213 auto* point_new = msg_compensated->add_point();
214 point_new->set_intensity(point.intensity());
215 point_new->set_timestamp(point.timestamp());
216 point_new->set_x(static_cast<float>(p.x()));
217 point_new->set_y(static_cast<float>(p.y()));
218 point_new->set_z(static_cast<float>(p.z()));
219 }
220}
221
222} // namespace velodyne
223} // namespace drivers
224} // namespace apollo
double f
Cyber has builtin time type Time.
Definition time.h:31
uint64_t ToNanosecond() const
convert time to nanosecond.
Definition time.cc:83
static Time Now()
get the current time.
Definition time.cc:57
bool MotionCompensation(const std::shared_ptr< const PointCloud > &msg, std::shared_ptr< PointCloud > msg_compensated)
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const cyber::Time &target_time, const float timeout_second=0.01f, std::string *errstr=nullptr) const
Test if a transform is possible
Definition buffer.cc:195
virtual TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const cyber::Time &time, const float timeout_second=0.01f) const
Get the transform between two frames by frame ID.
Definition buffer.cc:168
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
float sin(Angle16 a)
Definition angle.cc:25
class register implement
Definition arena_queue.h:37
optional apollo::common::Quaternion rotation
optional apollo::common::Point3D translation