22 #include "Eigen/Eigen" 30 #include "modules/drivers/lidar/proto/velodyne_config.pb.h" 31 #include "modules/drivers/proto/pointcloud.pb.h" 43 explicit Compensator(
const CompensatorConfig& config) : config_(config) {}
47 std::shared_ptr<PointCloud> msg_compensated);
54 bool QueryPoseAffineFromTF2(
const uint64_t& timestamp,
void* pose,
55 const std::string& child_frame_id);
61 std::shared_ptr<PointCloud> msg_compensated,
62 const uint64_t timestamp_min,
63 const uint64_t timestamp_max,
69 inline void GetTimestampInterval(
const std::shared_ptr<const PointCloud>& msg,
70 uint64_t* timestamp_min,
71 uint64_t* timestamp_max);
76 CompensatorConfig config_;
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool MotionCompensation(const std::shared_ptr< const PointCloud > &msg, std::shared_ptr< PointCloud > msg_compensated)
pcl::PointCloud< Point > PointCloud
Definition: types.h:64
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
Compensator(const CompensatorConfig &config)
Definition: compensator.h:43
Definition: compensator.h:41
virtual ~Compensator()
Definition: compensator.h:44
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34