17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_COST_FUNCTION_3D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_COST_FUNCTION_3D_H_ 21 #include "Eigen/Geometry" 22 #include "ceres/ceres.h" 31 const double scaling_factor,
32 const Eigen::Vector3d& delta_velocity_imu_frame,
33 const double first_delta_time_seconds,
34 const double second_delta_time_seconds) {
35 return new ceres::AutoDiffCostFunction<
41 first_delta_time_seconds,
42 second_delta_time_seconds));
46 bool operator()(
const T*
const middle_rotation,
const T*
const start_position,
47 const T*
const middle_position,
const T*
const end_position,
48 const T*
const gravity_constant,
49 const T*
const imu_calibration, T* residual)
const {
50 const Eigen::Quaternion<T> eigen_imu_calibration(
51 imu_calibration[0], imu_calibration[1], imu_calibration[2],
53 const Eigen::Matrix<T, 3, 1> imu_delta_velocity =
54 ToEigen(middle_rotation) * eigen_imu_calibration *
58 Eigen::Vector3d::UnitZ())
60 const Eigen::Matrix<T, 3, 1> start_velocity =
61 (Eigen::Map<const Eigen::Matrix<T, 3, 1>>(middle_position) -
62 Eigen::Map<
const Eigen::Matrix<T, 3, 1>>(start_position)) /
64 const Eigen::Matrix<T, 3, 1> end_velocity =
65 (Eigen::Map<const Eigen::Matrix<T, 3, 1>>(end_position) -
66 Eigen::Map<
const Eigen::Matrix<T, 3, 1>>(middle_position)) /
68 const Eigen::Matrix<T, 3, 1> delta_velocity = end_velocity - start_velocity;
70 (Eigen::Map<Eigen::Matrix<T, 3, 1>>(residual) =
77 const Eigen::Vector3d& delta_velocity_imu_frame,
78 const double first_delta_time_seconds,
79 const double second_delta_time_seconds)
90 static Eigen::Quaternion<T>
ToEigen(
const T*
const quaternion) {
91 return Eigen::Quaternion<T>(quaternion[0], quaternion[1], quaternion[2],
104 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_COST_FUNCTION_3D_H_ AccelerationCostFunction3D(const double scaling_factor, const Eigen::Vector3d &delta_velocity_imu_frame, const double first_delta_time_seconds, const double second_delta_time_seconds)
static Eigen::Quaternion< T > ToEigen(const T *const quaternion)
AccelerationCostFunction3D & operator=(const AccelerationCostFunction3D &)=delete
const double second_delta_time_seconds_
const double scaling_factor_
const double first_delta_time_seconds_
const Eigen::Vector3d delta_velocity_imu_frame_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Vector3d &delta_velocity_imu_frame, const double first_delta_time_seconds, const double second_delta_time_seconds)
bool operator()(const T *const middle_rotation, const T *const start_position, const T *const middle_position, const T *const end_position, const T *const gravity_constant, const T *const imu_calibration, T *residual) const