translation_delta_cost_functor_2d.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 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_MAPPING_INTERNAL_2D_SCAN_MATCHING_TRANSLATION_DELTA_COST_FUNCTOR_2D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_TRANSLATION_DELTA_COST_FUNCTOR_2D_H_
00019 
00020 #include "Eigen/Core"
00021 #include "ceres/ceres.h"
00022 
00023 namespace cartographer {
00024 namespace mapping {
00025 namespace scan_matching {
00026 
00027 // Computes the cost of translating 'pose' to 'target_translation'.
00028 // Cost increases with the solution's distance from 'target_translation'.
00029 class TranslationDeltaCostFunctor2D {
00030  public:
00031   static ceres::CostFunction* CreateAutoDiffCostFunction(
00032       const double scaling_factor, const Eigen::Vector2d& target_translation) {
00033     return new ceres::AutoDiffCostFunction<TranslationDeltaCostFunctor2D,
00034                                            2 /* residuals */,
00035                                            3 /* pose variables */>(
00036         new TranslationDeltaCostFunctor2D(scaling_factor, target_translation));
00037   }
00038 
00039   template <typename T>
00040   bool operator()(const T* const pose, T* residual) const {
00041     residual[0] = scaling_factor_ * (pose[0] - x_);
00042     residual[1] = scaling_factor_ * (pose[1] - y_);
00043     return true;
00044   }
00045 
00046  private:
00047   // Constructs a new TranslationDeltaCostFunctor2D from the given
00048   // 'target_translation' (x, y).
00049   explicit TranslationDeltaCostFunctor2D(
00050       const double scaling_factor, const Eigen::Vector2d& target_translation)
00051       : scaling_factor_(scaling_factor),
00052         x_(target_translation.x()),
00053         y_(target_translation.y()) {}
00054 
00055   TranslationDeltaCostFunctor2D(const TranslationDeltaCostFunctor2D&) = delete;
00056   TranslationDeltaCostFunctor2D& operator=(
00057       const TranslationDeltaCostFunctor2D&) = delete;
00058 
00059   const double scaling_factor_;
00060   const double x_;
00061   const double y_;
00062 };
00063 
00064 }  // namespace scan_matching
00065 }  // namespace mapping
00066 }  // namespace cartographer
00067 
00068 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_TRANSLATION_DELTA_COST_FUNCTOR_2D_H_


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