serialization.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2018 The Cartographer Authors
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 namespace cartographer {
20 namespace cloud {
21 
22 void CreateSensorMetadata(const std::string& sensor_id, const int trajectory_id,
23  proto::SensorMetadata* proto) {
24  proto->set_sensor_id(sensor_id);
25  proto->set_trajectory_id(trajectory_id);
26 }
27 
29  const std::string& sensor_id, int trajectory_id,
30  const sensor::proto::FixedFramePoseData& fixed_frame_pose_data,
31  proto::AddFixedFramePoseDataRequest* proto) {
32  CreateSensorMetadata(sensor_id, trajectory_id,
33  proto->mutable_sensor_metadata());
34  *proto->mutable_fixed_frame_pose_data() = fixed_frame_pose_data;
35 }
36 
37 void CreateAddImuDataRequest(const std::string& sensor_id,
38  const int trajectory_id,
39  const sensor::proto::ImuData& imu_data,
40  proto::AddImuDataRequest* proto) {
41  CreateSensorMetadata(sensor_id, trajectory_id,
42  proto->mutable_sensor_metadata());
43  *proto->mutable_imu_data() = imu_data;
44 }
45 
47  const std::string& sensor_id, int trajectory_id,
48  const sensor::proto::OdometryData& odometry_data,
49  proto::AddOdometryDataRequest* proto) {
50  CreateSensorMetadata(sensor_id, trajectory_id,
51  proto->mutable_sensor_metadata());
52  *proto->mutable_odometry_data() = odometry_data;
53 }
54 
56  const std::string& sensor_id, int trajectory_id,
57  const sensor::proto::TimedPointCloudData& timed_point_cloud_data,
58  proto::AddRangefinderDataRequest* proto) {
59  CreateSensorMetadata(sensor_id, trajectory_id,
60  proto->mutable_sensor_metadata());
61  *proto->mutable_timed_point_cloud_data() = timed_point_cloud_data;
62 }
63 
65  const std::string& sensor_id, int trajectory_id,
66  const sensor::proto::LandmarkData& landmark_data,
67  proto::AddLandmarkDataRequest* proto) {
68  CreateSensorMetadata(sensor_id, trajectory_id,
69  proto->mutable_sensor_metadata());
70  *proto->mutable_landmark_data() = landmark_data;
71 }
72 
74  const std::string& sensor_id, int trajectory_id, common::Time time,
75  int starting_submap_index,
77  insertion_result,
78  proto::SensorData* proto) {
79  CreateSensorMetadata(sensor_id, trajectory_id,
80  proto->mutable_sensor_metadata());
81  proto->mutable_local_slam_result_data()->set_timestamp(
82  common::ToUniversal(time));
83  *proto->mutable_local_slam_result_data()->mutable_node_data() =
84  mapping::ToProto(*insertion_result.constant_data);
85  for (const auto& insertion_submap : insertion_result.insertion_submaps) {
86  // We only send the probability grid up if the submap is finished.
87  auto* submap = proto->mutable_local_slam_result_data()->add_submaps();
88  insertion_submap->ToProto(submap, insertion_submap->finished());
89  submap->mutable_submap_id()->set_trajectory_id(trajectory_id);
90  submap->mutable_submap_id()->set_submap_index(starting_submap_index);
91  ++starting_submap_index;
92  }
93 }
94 
98  proto::SensorType type;
99  switch (sensor_id.type) {
100  case SensorType::RANGE:
101  type = proto::SensorType::RANGE;
102  break;
103  case SensorType::IMU:
104  type = proto::SensorType::IMU;
105  break;
106  case SensorType::ODOMETRY:
107  type = proto::SensorType::ODOMETRY;
108  break;
109  case SensorType::FIXED_FRAME_POSE:
110  type = proto::SensorType::FIXED_FRAME_POSE;
111  break;
112  case SensorType::LANDMARK:
113  type = proto::SensorType::LANDMARK;
114  break;
115  case SensorType::LOCAL_SLAM_RESULT:
116  type = proto::SensorType::LOCAL_SLAM_RESULT;
117  break;
118  default:
119  LOG(FATAL) << "unknown SensorType";
120  }
121  proto::SensorId proto;
122  proto.set_type(type);
123  proto.set_id(sensor_id.id);
124  return proto;
125 }
126 
128  const proto::SensorId& proto) {
130  using SensorType = SensorId::SensorType;
131  SensorType type;
132  switch (proto.type()) {
133  case proto::SensorType::RANGE:
134  type = SensorType::RANGE;
135  break;
136  case proto::SensorType::IMU:
137  type = SensorType::IMU;
138  break;
139  case proto::SensorType::ODOMETRY:
140  type = SensorType::ODOMETRY;
141  break;
142  case proto::SensorType::FIXED_FRAME_POSE:
143  type = SensorType::FIXED_FRAME_POSE;
144  break;
145  case proto::SensorType::LANDMARK:
146  type = SensorType::LANDMARK;
147  break;
148  case proto::SensorType::LOCAL_SLAM_RESULT:
149  type = SensorType::LOCAL_SLAM_RESULT;
150  break;
151  default:
152  LOG(FATAL) << "unknown proto::SensorType";
153  }
154  return SensorId{type, proto.id()};
155 }
156 
157 } // namespace cloud
158 } // namespace cartographer
mapping::TrajectoryBuilderInterface::SensorId FromProto(const proto::SensorId &proto)
void CreateAddRangeFinderDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::TimedPointCloudData &timed_point_cloud_data, proto::AddRangefinderDataRequest *proto)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
static time_point time
int64 ToUniversal(const Time time)
Definition: time.cc:36
void CreateAddOdometryDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::OdometryData &odometry_data, proto::AddOdometryDataRequest *proto)
void CreateAddFixedFramePoseDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::FixedFramePoseData &fixed_frame_pose_data, proto::AddFixedFramePoseDataRequest *proto)
void CreateAddLandmarkDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::LandmarkData &landmark_data, proto::AddLandmarkDataRequest *proto)
proto::MapLimits ToProto(const MapLimits &map_limits)
Definition: map_limits.h:92
void CreateSensorDataForLocalSlamResult(const std::string &sensor_id, int trajectory_id, common::Time time, int starting_submap_index, const mapping::TrajectoryBuilderInterface::InsertionResult &insertion_result, proto::SensorData *proto)
proto::SensorId ToProto(const mapping::TrajectoryBuilderInterface::SensorId &sensor_id)
void CreateAddImuDataRequest(const std::string &sensor_id, const int trajectory_id, const sensor::proto::ImuData &imu_data, proto::AddImuDataRequest *proto)
::cartographer::mapping::TrajectoryBuilderInterface::SensorId SensorId
void CreateSensorMetadata(const std::string &sensor_id, const int trajectory_id, proto::SensorMetadata *proto)


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58