Apollo 11.0
自动驾驶开放平台
compensator.h
浏览该文件的文档.
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
17#pragma once
18
19#include <memory>
20#include <string>
21
22#include "Eigen/Eigen"
23
24// Eigen 3.3.7: #define ALIVE (0)
25// fastrtps: enum ChangeKind_t { ALIVE, ... };
26#if defined(ALIVE)
27#undef ALIVE
28#endif
29
30#include "modules/common_msgs/sensor_msgs/pointcloud.pb.h"
31#include "modules/drivers/lidar/compensator/proto/compensator_config.pb.h"
32
34
35namespace apollo {
36namespace drivers {
37namespace compensator {
38
40
42 public:
43 explicit Compensator(const CompensatorConfig& config) : config_(config) {}
44 virtual ~Compensator() {}
45
47 const std::shared_ptr<const PointCloud>& msg,
48 std::shared_ptr<PointCloud> msg_compensated);
49
50 private:
55 bool QueryPoseAffineFromTF2(
56 const uint64_t& timestamp,
57 void* pose,
58 const std::string& child_frame_id);
59
64 const std::shared_ptr<const PointCloud>& msg,
65 std::shared_ptr<PointCloud> msg_compensated,
66 const uint64_t timestamp_min,
67 const uint64_t timestamp_max,
68 const Eigen::Affine3d& pose_min_time,
69 const Eigen::Affine3d& pose_max_time);
73 inline void GetTimestampInterval(
74 const std::shared_ptr<const PointCloud>& msg,
75 uint64_t* timestamp_min,
76 uint64_t* timestamp_max);
77
78 bool IsValid(const Eigen::Vector3d& point);
79
80 transform::Buffer* tf2_buffer_ptr_ = transform::Buffer::Instance();
81 CompensatorConfig config_;
82};
83
84} // namespace compensator
85} // namespace drivers
86} // namespace apollo
bool MotionCompensation(const std::shared_ptr< const PointCloud > &msg, std::shared_ptr< PointCloud > msg_compensated)
Compensator(const CompensatorConfig &config)
Definition compensator.h:43
class register implement
Definition arena_queue.h:37