17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_SPA_COST_FUNCTION_3D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_SPA_COST_FUNCTION_3D_H_ 23 #include "Eigen/Geometry" 29 #include "ceres/ceres.h" 30 #include "ceres/jet.h" 34 namespace optimization {
39 const PoseGraph::Constraint::Pose&
pose) {
40 return new ceres::AutoDiffCostFunction<
47 bool operator()(
const T*
const c_i_rotation,
const T*
const c_i_translation,
48 const T*
const c_j_rotation,
const T*
const c_j_translation,
52 c_j_rotation, c_j_translation),
53 pose_.translation_weight,
pose_.rotation_weight);
54 std::copy(std::begin(error), std::end(error), e);
62 const PoseGraph::Constraint::Pose
pose_;
69 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_SPA_COST_FUNCTION_3D_H_
bool operator()(const T *const c_i_rotation, const T *const c_i_translation, const T *const c_j_rotation, const T *const c_j_translation, T *const e) const
const PoseGraph::Constraint::Pose pose_
SpaCostFunction3D(const PoseGraph::Constraint::Pose &pose)
std::array< T, 3 > ScaleError(const std::array< T, 3 > &error, double translation_weight, double rotation_weight)
static std::array< T, 3 > ComputeUnscaledError(const transform::Rigid2d &relative_pose, const T *const start, const T *const end)
static ceres::CostFunction * CreateAutoDiffCostFunction(const PoseGraph::Constraint::Pose &pose)