28 proto::TrajectoryNodeData proto;
30 *proto.mutable_gravity_alignment() =
32 *proto.mutable_filtered_gravity_aligned_point_cloud() =
36 *proto.mutable_high_resolution_point_cloud() =
39 *proto.mutable_low_resolution_point_cloud() =
42 for (Eigen::VectorXf::Index i = 0;
44 proto.add_rotational_scan_matcher_histogram(
52 Eigen::VectorXf rotational_scan_matcher_histogram(
53 proto.rotational_scan_matcher_histogram_size());
54 for (
int i = 0; i != proto.rotational_scan_matcher_histogram_size(); ++i) {
55 rotational_scan_matcher_histogram(i) =
56 proto.rotational_scan_matcher_histogram(i);
67 rotational_scan_matcher_histogram,
PoseGraph::Constraint::Tag FromProto(const proto::PoseGraph::Constraint::Tag &proto)
sensor::PointCloud high_resolution_point_cloud
proto::CompressedPointCloud ToProto() const
transform::Rigid3d local_pose
sensor::PointCloud filtered_gravity_aligned_point_cloud
Eigen::Quaterniond gravity_alignment
Time FromUniversal(const int64 ticks)
Eigen::VectorXf rotational_scan_matcher_histogram
int64 ToUniversal(const Time time)
proto::MapLimits ToProto(const MapLimits &map_limits)
sensor::PointCloud low_resolution_point_cloud