17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_H_ 21 #include "Eigen/Geometry" 27 #include "ceres/ceres.h" 28 #include "ceres/jet.h" 32 namespace optimization {
45 return new ceres::AutoDiffCostFunction<
54 bool operator()(
const T*
const prev_node_pose,
const T*
const next_node_pose,
55 const T*
const landmark_rotation,
56 const T*
const landmark_translation, T*
const e)
const {
57 const std::tuple<std::array<T, 4>, std::array<T, 3>>
64 std::get<0>(interpolated_rotation_and_translation).data(),
65 std::get<1>(interpolated_rotation_and_translation).data(),
66 landmark_rotation, landmark_translation),
68 std::copy(std::begin(error), std::end(error), e);
77 observation.landmark_to_tracking_transform),
98 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_LANDMARK_COST_FUNCTION_2D_H_ LandmarkCostFunction2D(const LandmarkObservation &observation, const NodeSpec2D &prev_node, const NodeSpec2D &next_node)
const transform::Rigid3d landmark_to_tracking_transform_
static ceres::CostFunction * CreateAutoDiffCostFunction(const LandmarkObservation &observation, const NodeSpec2D &prev_node, const NodeSpec2D &next_node)
const Eigen::Quaterniond next_node_gravity_alignment_
bool operator()(const T *const prev_node_pose, const T *const next_node_pose, const T *const landmark_rotation, const T *const landmark_translation, T *const e) const
const Eigen::Quaterniond prev_node_gravity_alignment_
const double rotation_weight_
std::array< T, 3 > ScaleError(const std::array< T, 3 > &error, double translation_weight, double rotation_weight)
double ToSeconds(const Duration duration)
const double interpolation_parameter_
std::tuple< std::array< T, 4 >, std::array< T, 3 > > InterpolateNodes2D(const T *const prev_node_pose, const Eigen::Quaterniond &prev_node_gravity_alignment, const T *const next_node_pose, const Eigen::Quaterniond &next_node_gravity_alignment, const double interpolation_parameter)
static std::array< T, 3 > ComputeUnscaledError(const transform::Rigid2d &relative_pose, const T *const start, const T *const end)
const double translation_weight_