Extract rotation parameterization to a separate file. (#479)
parent
96b71e227f
commit
449799719f
|
@ -0,0 +1,67 @@
|
||||||
|
/*
|
||||||
|
* Copyright 2016 The Cartographer Authors
|
||||||
|
*
|
||||||
|
* Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
* you may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef CARTOGRAPHER_MAPPING_3D_ROTATION_PARAMETERIZATION_H_
|
||||||
|
#define CARTOGRAPHER_MAPPING_3D_ROTATION_PARAMETERIZATION_H_
|
||||||
|
|
||||||
|
#include "cartographer/common/math.h"
|
||||||
|
#include "ceres/jet.h"
|
||||||
|
#include "ceres/rotation.h"
|
||||||
|
|
||||||
|
namespace cartographer {
|
||||||
|
namespace mapping_3d {
|
||||||
|
|
||||||
|
struct YawOnlyQuaternionPlus {
|
||||||
|
template <typename T>
|
||||||
|
bool operator()(const T* x, const T* delta, T* x_plus_delta) const {
|
||||||
|
const T clamped_delta = common::Clamp(delta[0], T(-0.5), T(0.5));
|
||||||
|
T q_delta[4];
|
||||||
|
q_delta[0] = ceres::sqrt(1. - clamped_delta * clamped_delta);
|
||||||
|
q_delta[1] = T(0.);
|
||||||
|
q_delta[2] = T(0.);
|
||||||
|
q_delta[3] = clamped_delta;
|
||||||
|
ceres::QuaternionProduct(q_delta, x, x_plus_delta);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct ConstantYawQuaternionPlus {
|
||||||
|
template <typename T>
|
||||||
|
bool operator()(const T* x, const T* delta, T* x_plus_delta) const {
|
||||||
|
const T delta_norm =
|
||||||
|
ceres::sqrt(common::Pow2(delta[0]) + common::Pow2(delta[1]));
|
||||||
|
const T sin_delta_over_delta =
|
||||||
|
delta_norm < 1e-6 ? T(1.) : ceres::sin(delta_norm) / delta_norm;
|
||||||
|
T q_delta[4];
|
||||||
|
q_delta[0] = delta_norm < 1e-6 ? T(1.) : ceres::cos(delta_norm);
|
||||||
|
q_delta[1] = sin_delta_over_delta * delta[0];
|
||||||
|
q_delta[2] = sin_delta_over_delta * delta[1];
|
||||||
|
q_delta[3] = T(0.);
|
||||||
|
// We apply the 'delta' which is interpreted as an angle-axis rotation
|
||||||
|
// vector in the xy-plane of the submap frame. This way we can align to
|
||||||
|
// gravity because rotations around the z-axis in the submap frame do not
|
||||||
|
// change gravity alignment, while disallowing random rotations of the map
|
||||||
|
// that have nothing to do with gravity alignment (i.e. we disallow steps
|
||||||
|
// just changing "yaw" of the complete map).
|
||||||
|
ceres::QuaternionProduct(x, q_delta, x_plus_delta);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace mapping_3d
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
|
#endif // CARTOGRAPHER_MAPPING_3D_ROTATION_PARAMETERIZATION_H_
|
|
@ -23,6 +23,7 @@
|
||||||
#include "cartographer/common/ceres_solver_options.h"
|
#include "cartographer/common/ceres_solver_options.h"
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "cartographer/mapping_3d/ceres_pose.h"
|
#include "cartographer/mapping_3d/ceres_pose.h"
|
||||||
|
#include "cartographer/mapping_3d/rotation_parameterization.h"
|
||||||
#include "cartographer/mapping_3d/scan_matching/occupied_space_cost_functor.h"
|
#include "cartographer/mapping_3d/scan_matching/occupied_space_cost_functor.h"
|
||||||
#include "cartographer/mapping_3d/scan_matching/rotation_delta_cost_functor.h"
|
#include "cartographer/mapping_3d/scan_matching/rotation_delta_cost_functor.h"
|
||||||
#include "cartographer/mapping_3d/scan_matching/translation_delta_cost_functor.h"
|
#include "cartographer/mapping_3d/scan_matching/translation_delta_cost_functor.h"
|
||||||
|
@ -34,23 +35,6 @@
|
||||||
namespace cartographer {
|
namespace cartographer {
|
||||||
namespace mapping_3d {
|
namespace mapping_3d {
|
||||||
namespace scan_matching {
|
namespace scan_matching {
|
||||||
namespace {
|
|
||||||
|
|
||||||
struct YawOnlyQuaternionPlus {
|
|
||||||
template <typename T>
|
|
||||||
bool operator()(const T* x, const T* delta, T* x_plus_delta) const {
|
|
||||||
const T clamped_delta = common::Clamp(delta[0], T(-0.5), T(0.5));
|
|
||||||
T q_delta[4];
|
|
||||||
q_delta[0] = ceres::sqrt(1. - clamped_delta * clamped_delta);
|
|
||||||
q_delta[1] = T(0.);
|
|
||||||
q_delta[2] = T(0.);
|
|
||||||
q_delta[3] = clamped_delta;
|
|
||||||
ceres::QuaternionProduct(q_delta, x, x_plus_delta);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
} // namespace
|
|
||||||
|
|
||||||
proto::CeresScanMatcherOptions CreateCeresScanMatcherOptions(
|
proto::CeresScanMatcherOptions CreateCeresScanMatcherOptions(
|
||||||
common::LuaParameterDictionary* const parameter_dictionary) {
|
common::LuaParameterDictionary* const parameter_dictionary) {
|
||||||
|
|
|
@ -33,6 +33,7 @@
|
||||||
#include "cartographer/mapping_3d/ceres_pose.h"
|
#include "cartographer/mapping_3d/ceres_pose.h"
|
||||||
#include "cartographer/mapping_3d/imu_integration.h"
|
#include "cartographer/mapping_3d/imu_integration.h"
|
||||||
#include "cartographer/mapping_3d/rotation_cost_function.h"
|
#include "cartographer/mapping_3d/rotation_cost_function.h"
|
||||||
|
#include "cartographer/mapping_3d/rotation_parameterization.h"
|
||||||
#include "cartographer/mapping_3d/sparse_pose_graph/spa_cost_function.h"
|
#include "cartographer/mapping_3d/sparse_pose_graph/spa_cost_function.h"
|
||||||
#include "cartographer/transform/transform.h"
|
#include "cartographer/transform/transform.h"
|
||||||
#include "ceres/ceres.h"
|
#include "ceres/ceres.h"
|
||||||
|
@ -44,33 +45,6 @@ namespace cartographer {
|
||||||
namespace mapping_3d {
|
namespace mapping_3d {
|
||||||
namespace sparse_pose_graph {
|
namespace sparse_pose_graph {
|
||||||
|
|
||||||
namespace {
|
|
||||||
|
|
||||||
struct ConstantYawQuaternionPlus {
|
|
||||||
template <typename T>
|
|
||||||
bool operator()(const T* x, const T* delta, T* x_plus_delta) const {
|
|
||||||
const T delta_norm =
|
|
||||||
ceres::sqrt(common::Pow2(delta[0]) + common::Pow2(delta[1]));
|
|
||||||
const T sin_delta_over_delta =
|
|
||||||
delta_norm < 1e-6 ? T(1.) : ceres::sin(delta_norm) / delta_norm;
|
|
||||||
T q_delta[4];
|
|
||||||
q_delta[0] = delta_norm < 1e-6 ? T(1.) : ceres::cos(delta_norm);
|
|
||||||
q_delta[1] = sin_delta_over_delta * delta[0];
|
|
||||||
q_delta[2] = sin_delta_over_delta * delta[1];
|
|
||||||
q_delta[3] = T(0.);
|
|
||||||
// We apply the 'delta' which is interpreted as an angle-axis rotation
|
|
||||||
// vector in the xy-plane of the submap frame. This way we can align to
|
|
||||||
// gravity because rotations around the z-axis in the submap frame do not
|
|
||||||
// change gravity alignment, while disallowing random rotations of the map
|
|
||||||
// that have nothing to do with gravity alignment (i.e. we disallow steps
|
|
||||||
// just changing "yaw" of the complete map).
|
|
||||||
ceres::QuaternionProduct(x, q_delta, x_plus_delta);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
} // namespace
|
|
||||||
|
|
||||||
OptimizationProblem::OptimizationProblem(
|
OptimizationProblem::OptimizationProblem(
|
||||||
const mapping::sparse_pose_graph::proto::OptimizationProblemOptions&
|
const mapping::sparse_pose_graph::proto::OptimizationProblemOptions&
|
||||||
options,
|
options,
|
||||||
|
|
Loading…
Reference in New Issue