serialization.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/cloud/internal/sensor/serialization.h"
00018 
00019 namespace cartographer {
00020 namespace cloud {
00021 
00022 void CreateSensorMetadata(const std::string& sensor_id, const int trajectory_id,
00023                           const std::string& client_id,
00024                           proto::SensorMetadata* proto) {
00025   proto->set_sensor_id(sensor_id);
00026   proto->set_trajectory_id(trajectory_id);
00027   proto->set_client_id(client_id);
00028 }
00029 
00030 void CreateAddFixedFramePoseDataRequest(
00031     const std::string& sensor_id, int trajectory_id,
00032     const std::string& client_id,
00033     const sensor::proto::FixedFramePoseData& fixed_frame_pose_data,
00034     proto::AddFixedFramePoseDataRequest* proto) {
00035   CreateSensorMetadata(sensor_id, trajectory_id, client_id,
00036                        proto->mutable_sensor_metadata());
00037   *proto->mutable_fixed_frame_pose_data() = fixed_frame_pose_data;
00038 }
00039 
00040 void CreateAddImuDataRequest(const std::string& sensor_id,
00041                              const int trajectory_id,
00042                              const std::string& client_id,
00043                              const sensor::proto::ImuData& imu_data,
00044                              proto::AddImuDataRequest* proto) {
00045   CreateSensorMetadata(sensor_id, trajectory_id, client_id,
00046                        proto->mutable_sensor_metadata());
00047   *proto->mutable_imu_data() = imu_data;
00048 }
00049 
00050 void CreateAddOdometryDataRequest(
00051     const std::string& sensor_id, int trajectory_id,
00052     const std::string& client_id,
00053     const sensor::proto::OdometryData& odometry_data,
00054     proto::AddOdometryDataRequest* proto) {
00055   CreateSensorMetadata(sensor_id, trajectory_id, client_id,
00056                        proto->mutable_sensor_metadata());
00057   *proto->mutable_odometry_data() = odometry_data;
00058 }
00059 
00060 void CreateAddRangeFinderDataRequest(
00061     const std::string& sensor_id, int trajectory_id,
00062     const std::string& client_id,
00063     const sensor::proto::TimedPointCloudData& timed_point_cloud_data,
00064     proto::AddRangefinderDataRequest* proto) {
00065   CreateSensorMetadata(sensor_id, trajectory_id, client_id,
00066                        proto->mutable_sensor_metadata());
00067   *proto->mutable_timed_point_cloud_data() = timed_point_cloud_data;
00068 }
00069 
00070 void CreateAddLandmarkDataRequest(
00071     const std::string& sensor_id, int trajectory_id,
00072     const std::string& client_id,
00073     const sensor::proto::LandmarkData& landmark_data,
00074     proto::AddLandmarkDataRequest* proto) {
00075   CreateSensorMetadata(sensor_id, trajectory_id, client_id,
00076                        proto->mutable_sensor_metadata());
00077   *proto->mutable_landmark_data() = landmark_data;
00078 }
00079 
00080 void CreateSensorDataForLocalSlamResult(
00081     const std::string& sensor_id, int trajectory_id,
00082     const std::string& client_id, common::Time time, int starting_submap_index,
00083     const mapping::TrajectoryBuilderInterface::InsertionResult&
00084         insertion_result,
00085     proto::SensorData* proto) {
00086   CreateSensorMetadata(sensor_id, trajectory_id, client_id,
00087                        proto->mutable_sensor_metadata());
00088   proto->mutable_local_slam_result_data()->set_timestamp(
00089       common::ToUniversal(time));
00090   *proto->mutable_local_slam_result_data()->mutable_node_data() =
00091       mapping::ToProto(*insertion_result.constant_data);
00092   for (const auto& insertion_submap : insertion_result.insertion_submaps) {
00093     // We only send the probability grid up if the submap is finished.
00094     auto* submap = proto->mutable_local_slam_result_data()->add_submaps();
00095     *submap = insertion_submap->ToProto(insertion_submap->insertion_finished());
00096     submap->mutable_submap_id()->set_trajectory_id(trajectory_id);
00097     submap->mutable_submap_id()->set_submap_index(starting_submap_index);
00098     ++starting_submap_index;
00099   }
00100 }
00101 
00102 proto::SensorId ToProto(
00103     const mapping::TrajectoryBuilderInterface::SensorId& sensor_id) {
00104   using SensorType = mapping::TrajectoryBuilderInterface::SensorId::SensorType;
00105   proto::SensorType type;
00106   switch (sensor_id.type) {
00107     case SensorType::RANGE:
00108       type = proto::SensorType::RANGE;
00109       break;
00110     case SensorType::IMU:
00111       type = proto::SensorType::IMU;
00112       break;
00113     case SensorType::ODOMETRY:
00114       type = proto::SensorType::ODOMETRY;
00115       break;
00116     case SensorType::FIXED_FRAME_POSE:
00117       type = proto::SensorType::FIXED_FRAME_POSE;
00118       break;
00119     case SensorType::LANDMARK:
00120       type = proto::SensorType::LANDMARK;
00121       break;
00122     case SensorType::LOCAL_SLAM_RESULT:
00123       type = proto::SensorType::LOCAL_SLAM_RESULT;
00124       break;
00125     default:
00126       LOG(FATAL) << "unknown SensorType";
00127   }
00128   proto::SensorId proto;
00129   proto.set_type(type);
00130   proto.set_id(sensor_id.id);
00131   return proto;
00132 }
00133 
00134 mapping::TrajectoryBuilderInterface::SensorId FromProto(
00135     const proto::SensorId& proto) {
00136   using SensorId = mapping::TrajectoryBuilderInterface::SensorId;
00137   using SensorType = SensorId::SensorType;
00138   SensorType type;
00139   switch (proto.type()) {
00140     case proto::SensorType::RANGE:
00141       type = SensorType::RANGE;
00142       break;
00143     case proto::SensorType::IMU:
00144       type = SensorType::IMU;
00145       break;
00146     case proto::SensorType::ODOMETRY:
00147       type = SensorType::ODOMETRY;
00148       break;
00149     case proto::SensorType::FIXED_FRAME_POSE:
00150       type = SensorType::FIXED_FRAME_POSE;
00151       break;
00152     case proto::SensorType::LANDMARK:
00153       type = SensorType::LANDMARK;
00154       break;
00155     case proto::SensorType::LOCAL_SLAM_RESULT:
00156       type = SensorType::LOCAL_SLAM_RESULT;
00157       break;
00158     default:
00159       LOG(FATAL) << "unknown proto::SensorType";
00160   }
00161   return SensorId{type, proto.id()};
00162 }
00163 
00164 }  // namespace cloud
00165 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:36