|
| 1 | +// Copyright 2015-2019 Autoware Foundation |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_HPP |
| 16 | +#define NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_HPP |
| 17 | + |
| 18 | +#include "ndt/omp.hpp" |
| 19 | + |
| 20 | +#include <vector> |
| 21 | + |
| 22 | +template <class PointSource, class PointTarget> |
| 23 | +NormalDistributionsTransformOMP<PointSource, PointTarget>::NormalDistributionsTransformOMP() |
| 24 | +: ndt_ptr_(new pclomp::NormalDistributionsTransform<PointSource, PointTarget>) |
| 25 | +{ |
| 26 | +} |
| 27 | + |
| 28 | +template <class PointSource, class PointTarget> |
| 29 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::align( |
| 30 | + pcl::PointCloud<PointSource> & output, const Eigen::Matrix4f & guess) |
| 31 | +{ |
| 32 | + ndt_ptr_->align(output, guess); |
| 33 | +} |
| 34 | + |
| 35 | +template <class PointSource, class PointTarget> |
| 36 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setInputTarget( |
| 37 | + const boost::shared_ptr<pcl::PointCloud<PointTarget>> & map_ptr) |
| 38 | +{ |
| 39 | + ndt_ptr_->setInputTarget(map_ptr); |
| 40 | +} |
| 41 | + |
| 42 | +template <class PointSource, class PointTarget> |
| 43 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setInputSource( |
| 44 | + const boost::shared_ptr<pcl::PointCloud<PointSource>> & scan_ptr) |
| 45 | +{ |
| 46 | + ndt_ptr_->setInputSource(scan_ptr); |
| 47 | +} |
| 48 | + |
| 49 | +template <class PointSource, class PointTarget> |
| 50 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setMaximumIterations(int max_iter) |
| 51 | +{ |
| 52 | + ndt_ptr_->setMaximumIterations(max_iter); |
| 53 | +} |
| 54 | + |
| 55 | +template <class PointSource, class PointTarget> |
| 56 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setResolution(float res) |
| 57 | +{ |
| 58 | + ndt_ptr_->setResolution(res); |
| 59 | +} |
| 60 | + |
| 61 | +template <class PointSource, class PointTarget> |
| 62 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setStepSize(double step_size) |
| 63 | +{ |
| 64 | + ndt_ptr_->setStepSize(step_size); |
| 65 | +} |
| 66 | + |
| 67 | +template <class PointSource, class PointTarget> |
| 68 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setTransformationEpsilon( |
| 69 | + double trans_eps) |
| 70 | +{ |
| 71 | + ndt_ptr_->setTransformationEpsilon(trans_eps); |
| 72 | +} |
| 73 | + |
| 74 | +template <class PointSource, class PointTarget> |
| 75 | +int NormalDistributionsTransformOMP<PointSource, PointTarget>::getMaximumIterations() |
| 76 | +{ |
| 77 | + return ndt_ptr_->getMaximumIterations(); |
| 78 | +} |
| 79 | + |
| 80 | +template <class PointSource, class PointTarget> |
| 81 | +int NormalDistributionsTransformOMP<PointSource, PointTarget>::getFinalNumIteration() const |
| 82 | +{ |
| 83 | + return ndt_ptr_->getFinalNumIteration(); |
| 84 | +} |
| 85 | + |
| 86 | +template <class PointSource, class PointTarget> |
| 87 | +float NormalDistributionsTransformOMP<PointSource, PointTarget>::getResolution() const |
| 88 | +{ |
| 89 | + return ndt_ptr_->getResolution(); |
| 90 | +} |
| 91 | + |
| 92 | +template <class PointSource, class PointTarget> |
| 93 | +double NormalDistributionsTransformOMP<PointSource, PointTarget>::getStepSize() const |
| 94 | +{ |
| 95 | + return ndt_ptr_->getStepSize(); |
| 96 | +} |
| 97 | + |
| 98 | +template <class PointSource, class PointTarget> |
| 99 | +double NormalDistributionsTransformOMP<PointSource, PointTarget>::getTransformationEpsilon() |
| 100 | +{ |
| 101 | + return ndt_ptr_->getTransformationEpsilon(); |
| 102 | +} |
| 103 | + |
| 104 | +template <class PointSource, class PointTarget> |
| 105 | +double NormalDistributionsTransformOMP<PointSource, PointTarget>::getTransformationProbability() |
| 106 | + const |
| 107 | +{ |
| 108 | + return ndt_ptr_->getTransformationProbability(); |
| 109 | +} |
| 110 | + |
| 111 | +template <class PointSource, class PointTarget> |
| 112 | +double NormalDistributionsTransformOMP<PointSource, PointTarget>::getFitnessScore() |
| 113 | +{ |
| 114 | + return ndt_ptr_->getFitnessScore(); |
| 115 | +} |
| 116 | + |
| 117 | +template <class PointSource, class PointTarget> |
| 118 | +boost::shared_ptr<const pcl::PointCloud<PointTarget>> |
| 119 | +NormalDistributionsTransformOMP<PointSource, PointTarget>::getInputTarget() const |
| 120 | +{ |
| 121 | + return ndt_ptr_->getInputTarget(); |
| 122 | +} |
| 123 | + |
| 124 | +template <class PointSource, class PointTarget> |
| 125 | +boost::shared_ptr<const pcl::PointCloud<PointSource>> |
| 126 | +NormalDistributionsTransformOMP<PointSource, PointTarget>::getInputSource() const |
| 127 | +{ |
| 128 | + return ndt_ptr_->getInputSource(); |
| 129 | +} |
| 130 | + |
| 131 | +template <class PointSource, class PointTarget> |
| 132 | +Eigen::Matrix4f NormalDistributionsTransformOMP<PointSource, PointTarget>::getFinalTransformation() |
| 133 | + const |
| 134 | +{ |
| 135 | + return ndt_ptr_->getFinalTransformation(); |
| 136 | +} |
| 137 | + |
| 138 | +template <class PointSource, class PointTarget> |
| 139 | +std::vector<Eigen::Matrix4f> |
| 140 | +NormalDistributionsTransformOMP<PointSource, PointTarget>::getFinalTransformationArray() const |
| 141 | +{ |
| 142 | + return ndt_ptr_->getFinalTransformationArray(); |
| 143 | +} |
| 144 | + |
| 145 | +template <class PointSource, class PointTarget> |
| 146 | +Eigen::Matrix<double, 6, 6> NormalDistributionsTransformOMP<PointSource, PointTarget>::getHessian() |
| 147 | + const |
| 148 | +{ |
| 149 | + // return ndt_ptr_->getHessian(); |
| 150 | + return Eigen::Matrix<double, 6, 6>(); |
| 151 | +} |
| 152 | + |
| 153 | +template <class PointSource, class PointTarget> |
| 154 | +boost::shared_ptr<pcl::search::KdTree<PointTarget>> |
| 155 | +NormalDistributionsTransformOMP<PointSource, PointTarget>::getSearchMethodTarget() const |
| 156 | +{ |
| 157 | + return ndt_ptr_->getSearchMethodTarget(); |
| 158 | +} |
| 159 | + |
| 160 | +template <class PointSource, class PointTarget> |
| 161 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setNumThreads(int n) |
| 162 | +{ |
| 163 | + ndt_ptr_->setNumThreads(n); |
| 164 | +} |
| 165 | + |
| 166 | +template <class PointSource, class PointTarget> |
| 167 | +void NormalDistributionsTransformOMP<PointSource, PointTarget>::setNeighborhoodSearchMethod( |
| 168 | + pclomp::NeighborSearchMethod method) |
| 169 | +{ |
| 170 | + ndt_ptr_->setNeighborhoodSearchMethod(method); |
| 171 | +} |
| 172 | + |
| 173 | +template <class PointSource, class PointTarget> |
| 174 | +int NormalDistributionsTransformOMP<PointSource, PointTarget>::getNumThreads() const |
| 175 | +{ |
| 176 | + return ndt_ptr_->getNumThreads(); |
| 177 | +} |
| 178 | + |
| 179 | +template <class PointSource, class PointTarget> |
| 180 | +pclomp::NeighborSearchMethod |
| 181 | +NormalDistributionsTransformOMP<PointSource, PointTarget>::getNeighborhoodSearchMethod() const |
| 182 | +{ |
| 183 | + return ndt_ptr_->getNeighborhoodSearchMethod(); |
| 184 | +} |
| 185 | + |
| 186 | +#endif // NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_HPP |
0 commit comments