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;
35 <<
" frame_id:" << child_frame_id <<
" Error info: " << err_string;
44 }
catch (tf2::TransformException& ex) {
49 Eigen::Affine3d* tmp_pose = (Eigen::Affine3d*)pose;
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";
69 Eigen::Affine3d pose_min_time;
70 Eigen::Affine3d pose_max_time;
72 uint64_t timestamp_min = 0;
73 uint64_t timestamp_max = 0;
74 std::string frame_id = msg->header().frame_id();
75 GetTimestampInterval(msg, ×tamp_min, ×tamp_max);
77 msg_compensated->mutable_header()->set_timestamp_sec(
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());
87 AINFO <<
"compenstator new msg diff:" << new_time - start
88 <<
";meta:" << msg->header().lidar_timestamp();
89 msg_compensated->mutable_point()->Reserve(240000);
92 if (QueryPoseAffineFromTF2(timestamp_min, &pose_min_time, frame_id) &&
93 QueryPoseAffineFromTF2(timestamp_max, &pose_max_time, frame_id)) {
95 AINFO <<
"compenstator tf msg diff:" << tf_time - new_time
96 <<
";meta:" << msg->header().lidar_timestamp();
98 pose_min_time, pose_max_time);
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();
108inline void Compensator::GetTimestampInterval(
109 const std::shared_ptr<const PointCloud>& msg, uint64_t* timestamp_min,
110 uint64_t* timestamp_max) {
112 *timestamp_min = std::numeric_limits<uint64_t>::max();
114 for (
const auto& point : msg->point()) {
115 uint64_t timestamp = point.timestamp();
116 if (timestamp < *timestamp_min) {
117 *timestamp_min = timestamp;
120 if (timestamp > *timestamp_max) {
121 *timestamp_max = timestamp;
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) {
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());
142 translation = q_max.conjugate() * translation;
146 double d = q0.dot(q1);
147 double abs_d = abs(d);
148 double f = 1.0 /
static_cast<double>(timestamp_max - timestamp_min);
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)) {
164 auto* point_new = msg_compensated->add_point();
165 point_new->CopyFrom(point);
171 float y_scalar = point.y();
172 float z_scalar = point.z();
173 Eigen::Vector3d p(x_scalar, y_scalar, z_scalar);
175 uint64_t tp = point.timestamp();
176 double t =
static_cast<double>(timestamp_max - tp) *
f;
178 Eigen::Translation3d ti(t * translation);
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());
184 Eigen::Affine3d trans = ti * qi;
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()));
197 for (
auto& point : msg->point()) {
198 float x_scalar = point.x();
199 if (std::isnan(x_scalar)) {
203 float y_scalar = point.y();
204 float z_scalar = point.z();
205 Eigen::Vector3d p(x_scalar, y_scalar, z_scalar);
207 uint64_t tp = point.timestamp();
208 double t =
static_cast<double>(timestamp_max - tp) *
f;
209 Eigen::Translation3d ti(t * translation);
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()));
Cyber has builtin time type Time.
uint64_t ToNanosecond() const
convert time to nanosecond.
static Time Now()
get the current time.
bool MotionCompensation(const std::shared_ptr< const PointCloud > &msg, std::shared_ptr< PointCloud > msg_compensated)
optional string world_frame_id
optional float transform_query_timeout