Namespaces | |
| namespace | testing |
Classes | |
| class | AdaptiveVoxelFilter |
| class | Collator |
| class | CollatorInterface |
| class | CompressedPointCloud |
| class | Data |
| class | Dispatchable |
| struct | FixedFramePoseData |
| struct | ImuData |
| struct | LandmarkData |
| struct | LandmarkObservation |
| class | MapByTime |
| struct | OdometryData |
| class | OrderedMultiQueue |
| struct | PointCloudWithIntensities |
| struct | QueueKey |
| struct | RangeData |
| struct | RangefinderPoint |
| struct | TimedPointCloudData |
| struct | TimedPointCloudOriginData |
| struct | TimedRangeData |
| struct | TimedRangefinderPoint |
| class | TrajectoryCollator |
| class | VoxelFilter |
Functions | |
| proto::AdaptiveVoxelFilterOptions | CreateAdaptiveVoxelFilterOptions (common::LuaParameterDictionary *const parameter_dictionary) |
| PointCloud | CropPointCloud (const PointCloud &point_cloud, const float min_z, const float max_z) |
| RangeData | CropRangeData (const RangeData &range_data, const float min_z, const float max_z) |
| TimedPointCloud | CropTimedPointCloud (const TimedPointCloud &point_cloud, const float min_z, const float max_z) |
| TimedRangeData | CropTimedRangeData (const TimedRangeData &range_data, const float min_z, const float max_z) |
| OdometryData | FromProto (const proto::OdometryData &proto) |
| ImuData | FromProto (const proto::ImuData &proto) |
| FixedFramePoseData | FromProto (const proto::FixedFramePoseData &proto) |
| TimedPointCloudData | FromProto (const proto::TimedPointCloudData &proto) |
| LandmarkData | FromProto (const proto::LandmarkData &proto) |
| RangefinderPoint | FromProto (const proto::RangefinderPoint &rangefinder_point_proto) |
| RangeData | FromProto (const proto::RangeData &proto) |
| TimedRangefinderPoint | FromProto (const proto::TimedRangefinderPoint &timed_rangefinder_point_proto) |
| template<typename DataType > | |
| std::unique_ptr< Dispatchable < DataType > > | MakeDispatchable (const std::string &sensor_id, const DataType &data) |
| MATCHER_P (Near, point, std::string(negation?"Doesn't":"Does")+" match.") | |
| template<class T > | |
| RangefinderPoint | operator* (const transform::Rigid3< T > &lhs, const RangefinderPoint &rhs) |
| template<class T > | |
| TimedRangefinderPoint | operator* (const transform::Rigid3< T > &lhs, const TimedRangefinderPoint &rhs) |
| std::ostream & | operator<< (std::ostream &out, const QueueKey &key) |
| bool | operator== (const RangefinderPoint &lhs, const RangefinderPoint &rhs) |
| bool | operator== (const TimedRangefinderPoint &lhs, const TimedRangefinderPoint &rhs) |
| proto::LandmarkData | ToProto (const LandmarkData &landmark_data) |
| proto::OdometryData | ToProto (const OdometryData &odometry_data) |
| proto::ImuData | ToProto (const ImuData &imu_data) |
| proto::FixedFramePoseData | ToProto (const FixedFramePoseData &pose_data) |
| proto::TimedPointCloudData | ToProto (const TimedPointCloudData &timed_point_cloud_data) |
| proto::RangeData | ToProto (const RangeData &range_data) |
| proto::RangefinderPoint | ToProto (const RangefinderPoint &rangefinder_point) |
| proto::TimedRangefinderPoint | ToProto (const TimedRangefinderPoint &timed_rangefinder_point) |
| RangefinderPoint | ToRangefinderPoint (const TimedRangefinderPoint &timed_rangefinder_point) |
| TimedRangefinderPoint | ToTimedRangefinderPoint (const RangefinderPoint &rangefinder_point, const float time) |
| PointCloud | TransformPointCloud (const PointCloud &point_cloud, const transform::Rigid3f &transform) |
| RangeData | TransformRangeData (const RangeData &range_data, const transform::Rigid3f &transform) |
| TimedPointCloud | TransformTimedPointCloud (const TimedPointCloud &point_cloud, const transform::Rigid3f &transform) |
| TimedRangeData | TransformTimedRangeData (const TimedRangeData &range_data, const transform::Rigid3f &transform) |
| proto::AdaptiveVoxelFilterOptions cartographer::sensor::CreateAdaptiveVoxelFilterOptions | ( | common::LuaParameterDictionary *const | parameter_dictionary | ) |
Definition at line 133 of file voxel_filter.cc.
| PointCloud cartographer::sensor::CropPointCloud | ( | const PointCloud & | point_cloud, |
| const float | min_z, | ||
| const float | max_z | ||
| ) |
Definition at line 45 of file point_cloud.cc.
| RangeData cartographer::sensor::CropRangeData | ( | const RangeData & | range_data, |
| const float | min_z, | ||
| const float | max_z | ||
| ) |
Definition at line 43 of file range_data.cc.
| TimedPointCloud cartographer::sensor::CropTimedPointCloud | ( | const TimedPointCloud & | point_cloud, |
| const float | min_z, | ||
| const float | max_z | ||
| ) |
Definition at line 56 of file point_cloud.cc.
| TimedRangeData cartographer::sensor::CropTimedRangeData | ( | const TimedRangeData & | range_data, |
| const float | min_z, | ||
| const float | max_z | ||
| ) |
Definition at line 50 of file range_data.cc.
| OdometryData cartographer::sensor::FromProto | ( | const proto::OdometryData & | proto | ) |
Definition at line 31 of file odometry_data.cc.
| ImuData cartographer::sensor::FromProto | ( | const proto::ImuData & | proto | ) |
Definition at line 34 of file imu_data.cc.
| FixedFramePoseData cartographer::sensor::FromProto | ( | const proto::FixedFramePoseData & | proto | ) |
Definition at line 34 of file fixed_frame_pose_data.cc.
| TimedPointCloudData cartographer::sensor::FromProto | ( | const proto::TimedPointCloudData & | proto | ) |
Definition at line 37 of file timed_point_cloud_data.cc.
| LandmarkData cartographer::sensor::FromProto | ( | const proto::LandmarkData & | proto | ) |
Definition at line 38 of file landmark_data.cc.
| RangefinderPoint cartographer::sensor::FromProto | ( | const proto::RangefinderPoint & | rangefinder_point_proto | ) | [inline] |
Definition at line 68 of file rangefinder_point.h.
| RangeData cartographer::sensor::FromProto | ( | const proto::RangeData & | proto | ) |
Definition at line 71 of file range_data.cc.
| TimedRangefinderPoint cartographer::sensor::FromProto | ( | const proto::TimedRangefinderPoint & | timed_rangefinder_point_proto | ) | [inline] |
Definition at line 80 of file rangefinder_point.h.
| std::unique_ptr<Dispatchable<DataType> > cartographer::sensor::MakeDispatchable | ( | const std::string & | sensor_id, |
| const DataType & | data | ||
| ) |
Definition at line 44 of file dispatchable.h.
| cartographer::sensor::MATCHER_P | ( | Near | , |
| point | , | ||
| std::string(negation?"Doesn't":"Does")+" match." | |||
| ) |
Definition at line 35 of file sensor/internal/test_helpers.h.
| RangefinderPoint cartographer::sensor::operator* | ( | const transform::Rigid3< T > & | lhs, |
| const RangefinderPoint & | rhs | ||
| ) | [inline] |
Definition at line 43 of file rangefinder_point.h.
| TimedRangefinderPoint cartographer::sensor::operator* | ( | const transform::Rigid3< T > & | lhs, |
| const TimedRangefinderPoint & | rhs | ||
| ) | [inline] |
Definition at line 51 of file rangefinder_point.h.
| std::ostream& cartographer::sensor::operator<< | ( | std::ostream & | out, |
| const QueueKey & | key | ||
| ) | [inline] |
Definition at line 37 of file ordered_multi_queue.cc.
| bool cartographer::sensor::operator== | ( | const RangefinderPoint & | lhs, |
| const RangefinderPoint & | rhs | ||
| ) | [inline] |
Definition at line 58 of file rangefinder_point.h.
| bool cartographer::sensor::operator== | ( | const TimedRangefinderPoint & | lhs, |
| const TimedRangefinderPoint & | rhs | ||
| ) | [inline] |
Definition at line 63 of file rangefinder_point.h.
| proto::LandmarkData cartographer::sensor::ToProto | ( | const LandmarkData & | landmark_data | ) |
Definition at line 24 of file landmark_data.cc.
| proto::OdometryData cartographer::sensor::ToProto | ( | const OdometryData & | odometry_data | ) |
Definition at line 24 of file odometry_data.cc.
| proto::ImuData cartographer::sensor::ToProto | ( | const ImuData & | imu_data | ) |
Definition at line 24 of file imu_data.cc.
| proto::FixedFramePoseData cartographer::sensor::ToProto | ( | const FixedFramePoseData & | pose_data | ) |
Definition at line 25 of file fixed_frame_pose_data.cc.
| proto::TimedPointCloudData cartographer::sensor::ToProto | ( | const TimedPointCloudData & | timed_point_cloud_data | ) |
Definition at line 25 of file timed_point_cloud_data.cc.
| proto::RangeData cartographer::sensor::ToProto | ( | const RangeData & | range_data | ) |
Definition at line 57 of file range_data.cc.
| proto::RangefinderPoint cartographer::sensor::ToProto | ( | const RangefinderPoint & | rangefinder_point | ) | [inline] |
Definition at line 73 of file rangefinder_point.h.
| proto::TimedRangefinderPoint cartographer::sensor::ToProto | ( | const TimedRangefinderPoint & | timed_rangefinder_point | ) | [inline] |
Definition at line 86 of file rangefinder_point.h.
| RangefinderPoint cartographer::sensor::ToRangefinderPoint | ( | const TimedRangefinderPoint & | timed_rangefinder_point | ) | [inline] |
Definition at line 95 of file rangefinder_point.h.
| TimedRangefinderPoint cartographer::sensor::ToTimedRangefinderPoint | ( | const RangefinderPoint & | rangefinder_point, |
| const float | time | ||
| ) | [inline] |
Definition at line 100 of file rangefinder_point.h.
| PointCloud cartographer::sensor::TransformPointCloud | ( | const PointCloud & | point_cloud, |
| const transform::Rigid3f & | transform | ||
| ) |
Definition at line 25 of file point_cloud.cc.
| RangeData cartographer::sensor::TransformRangeData | ( | const RangeData & | range_data, |
| const transform::Rigid3f & | transform | ||
| ) |
Definition at line 25 of file range_data.cc.
| TimedPointCloud cartographer::sensor::TransformTimedPointCloud | ( | const TimedPointCloud & | point_cloud, |
| const transform::Rigid3f & | transform | ||
| ) |
Definition at line 35 of file point_cloud.cc.
| TimedRangeData cartographer::sensor::TransformTimedRangeData | ( | const TimedRangeData & | range_data, |
| const transform::Rigid3f & | transform | ||
| ) |
Definition at line 34 of file range_data.cc.