rangefinder_point.h
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 #ifndef CARTOGRAPHER_SENSOR_RANGEFINDER_POINT_H_
00018 #define CARTOGRAPHER_SENSOR_RANGEFINDER_POINT_H_
00019 
00020 #include <vector>
00021 
00022 #include "Eigen/Core"
00023 #include "cartographer/sensor/proto/sensor.pb.h"
00024 #include "cartographer/transform/transform.h"
00025 #include "glog/logging.h"
00026 
00027 namespace cartographer {
00028 namespace sensor {
00029 
00030 // Stores 3D position of a point observed by a rangefinder sensor.
00031 struct RangefinderPoint {
00032   Eigen::Vector3f position;
00033 };
00034 
00035 // Stores 3D position of a point with its relative measurement time.
00036 // See point_cloud.h for more details.
00037 struct TimedRangefinderPoint {
00038   Eigen::Vector3f position;
00039   float time;
00040 };
00041 
00042 template <class T>
00043 inline RangefinderPoint operator*(const transform::Rigid3<T>& lhs,
00044                                   const RangefinderPoint& rhs) {
00045   RangefinderPoint result = rhs;
00046   result.position = lhs * rhs.position;
00047   return result;
00048 }
00049 
00050 template <class T>
00051 inline TimedRangefinderPoint operator*(const transform::Rigid3<T>& lhs,
00052                                        const TimedRangefinderPoint& rhs) {
00053   TimedRangefinderPoint result = rhs;
00054   result.position = lhs * rhs.position;
00055   return result;
00056 }
00057 
00058 inline bool operator==(const RangefinderPoint& lhs,
00059                        const RangefinderPoint& rhs) {
00060   return lhs.position == rhs.position;
00061 }
00062 
00063 inline bool operator==(const TimedRangefinderPoint& lhs,
00064                        const TimedRangefinderPoint& rhs) {
00065   return lhs.position == rhs.position && lhs.time == rhs.time;
00066 }
00067 
00068 inline RangefinderPoint FromProto(
00069     const proto::RangefinderPoint& rangefinder_point_proto) {
00070   return {transform::ToEigen(rangefinder_point_proto.position())};
00071 }
00072 
00073 inline proto::RangefinderPoint ToProto(
00074     const RangefinderPoint& rangefinder_point) {
00075   proto::RangefinderPoint proto;
00076   *proto.mutable_position() = transform::ToProto(rangefinder_point.position);
00077   return proto;
00078 }
00079 
00080 inline TimedRangefinderPoint FromProto(
00081     const proto::TimedRangefinderPoint& timed_rangefinder_point_proto) {
00082   return {transform::ToEigen(timed_rangefinder_point_proto.position()),
00083           timed_rangefinder_point_proto.time()};
00084 }
00085 
00086 inline proto::TimedRangefinderPoint ToProto(
00087     const TimedRangefinderPoint& timed_rangefinder_point) {
00088   proto::TimedRangefinderPoint proto;
00089   *proto.mutable_position() =
00090       transform::ToProto(timed_rangefinder_point.position);
00091   proto.set_time(timed_rangefinder_point.time);
00092   return proto;
00093 }
00094 
00095 inline RangefinderPoint ToRangefinderPoint(
00096     const TimedRangefinderPoint& timed_rangefinder_point) {
00097   return {timed_rangefinder_point.position};
00098 }
00099 
00100 inline TimedRangefinderPoint ToTimedRangefinderPoint(
00101     const RangefinderPoint& rangefinder_point, const float time) {
00102   return {rangefinder_point.position, time};
00103 }
00104 
00105 }  // namespace sensor
00106 }  // namespace cartographer
00107 
00108 #endif  // CARTOGRAPHER_SENSOR_RANGEFINDER_POINT_H_


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