landmark_cost_function_3d.h
Go to the documentation of this file.
1 /*
2  * Copyright 2018 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_3D_H_
19 
20 #include "Eigen/Core"
21 #include "Eigen/Geometry"
27 #include "ceres/ceres.h"
28 #include "ceres/jet.h"
29 
30 namespace cartographer {
31 namespace mapping {
32 namespace optimization {
33 
34 // Cost function measuring the weighted error between the observed pose given by
35 // the landmark measurement and the linearly interpolated pose.
37  public:
38  using LandmarkObservation =
40 
41  static ceres::CostFunction* CreateAutoDiffCostFunction(
42  const LandmarkObservation& observation, const NodeSpec3D& prev_node,
43  const NodeSpec3D& next_node) {
44  return new ceres::AutoDiffCostFunction<
45  LandmarkCostFunction3D, 6 /* residuals */,
46  4 /* previous node rotation variables */,
47  3 /* previous node translation variables */,
48  4 /* next node rotation variables */,
49  3 /* next node translation variables */,
50  4 /* landmark rotation variables */,
51  3 /* landmark translation variables */>(
52  new LandmarkCostFunction3D(observation, prev_node, next_node));
53  }
54 
55  template <typename T>
56  bool operator()(const T* const prev_node_rotation,
57  const T* const prev_node_translation,
58  const T* const next_node_rotation,
59  const T* const next_node_translation,
60  const T* const landmark_rotation,
61  const T* const landmark_translation, T* const e) const {
62  const std::tuple<std::array<T, 4>, std::array<T, 3>>
63  interpolated_rotation_and_translation = InterpolateNodes3D(
64  prev_node_rotation, prev_node_translation, next_node_rotation,
65  next_node_translation, interpolation_parameter_);
66  const std::array<T, 6> error = ScaleError(
69  std::get<0>(interpolated_rotation_and_translation).data(),
70  std::get<1>(interpolated_rotation_and_translation).data(),
71  landmark_rotation, landmark_translation),
73  std::copy(std::begin(error), std::end(error), e);
74  return true;
75  }
76 
77  private:
79  const NodeSpec3D& prev_node,
80  const NodeSpec3D& next_node)
82  observation.landmark_to_tracking_transform),
83  translation_weight_(observation.translation_weight),
84  rotation_weight_(observation.rotation_weight),
86  common::ToSeconds(observation.time - prev_node.time) /
87  common::ToSeconds(next_node.time - prev_node.time)) {}
88 
90  const double translation_weight_;
91  const double rotation_weight_;
93 };
94 
95 } // namespace optimization
96 } // namespace mapping
97 } // namespace cartographer
98 
99 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_3D_H_
static ceres::CostFunction * CreateAutoDiffCostFunction(const LandmarkObservation &observation, const NodeSpec3D &prev_node, const NodeSpec3D &next_node)
LandmarkCostFunction3D(const LandmarkObservation &observation, const NodeSpec3D &prev_node, const NodeSpec3D &next_node)
static time_point time
std::tuple< std::array< T, 4 >, std::array< T, 3 > > InterpolateNodes3D(const T *const prev_node_rotation, const T *const prev_node_translation, const T *const next_node_rotation, const T *const next_node_translation, const double interpolation_parameter)
std::array< T, 3 > ScaleError(const std::array< T, 3 > &error, double translation_weight, double rotation_weight)
double ToSeconds(const Duration duration)
Definition: time.cc:29
static std::array< T, 3 > ComputeUnscaledError(const transform::Rigid2d &relative_pose, const T *const start, const T *const end)
bool operator()(const T *const prev_node_rotation, const T *const prev_node_translation, const T *const next_node_rotation, const T *const next_node_translation, const T *const landmark_rotation, const T *const landmark_translation, T *const e) const


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58