#include <rotation_cost_function_3d.h>
|
| template<typename T > |
| bool | operator() (const T *const start_rotation, const T *const end_rotation, const T *const imu_calibration, T *residual) const |
| |
|
| static ceres::CostFunction * | CreateAutoDiffCostFunction (const double scaling_factor, const Eigen::Quaterniond &delta_rotation_imu_frame) |
| |
Definition at line 28 of file rotation_cost_function_3d.h.
◆ RotationCostFunction3D() [1/2]
| cartographer::mapping::RotationCostFunction3D::RotationCostFunction3D |
( |
const double |
scaling_factor, |
|
|
const Eigen::Quaterniond & |
delta_rotation_imu_frame |
|
) |
| |
|
inlineprivate |
◆ RotationCostFunction3D() [2/2]
◆ CreateAutoDiffCostFunction()
| static ceres::CostFunction* cartographer::mapping::RotationCostFunction3D::CreateAutoDiffCostFunction |
( |
const double |
scaling_factor, |
|
|
const Eigen::Quaterniond & |
delta_rotation_imu_frame |
|
) |
| |
|
inlinestatic |
◆ operator()()
template<typename T >
| bool cartographer::mapping::RotationCostFunction3D::operator() |
( |
const T *const |
start_rotation, |
|
|
const T *const |
end_rotation, |
|
|
const T *const |
imu_calibration, |
|
|
T * |
residual |
|
) |
| const |
|
inline |
◆ operator=()
◆ delta_rotation_imu_frame_
| const Eigen::Quaterniond cartographer::mapping::RotationCostFunction3D::delta_rotation_imu_frame_ |
|
private |
◆ scaling_factor_
| const double cartographer::mapping::RotationCostFunction3D::scaling_factor_ |
|
private |
The documentation for this class was generated from the following file: