#include <residuals.h>
|
| SymmetricPointToPlaneError (const Eigen::Vector3d &source_t_point, const Eigen::Vector3d &target_t_point, const Eigen::Vector3d &source_normal, const Eigen::Vector3d &target_normal) |
|
template<typename T > |
bool | operator() (const T *target_T_source_data, T *symmetric_point_to_plane_error) const |
|
|
static void | AddCostFunction (const Eigen::Vector3d &source_t_point, const Eigen::Vector3d &target_t_point, const Eigen::Vector3d &source_normal, const Eigen::Vector3d &target_normal, Eigen::Matrix< double, 6, 1 > &target_T_source, ceres::Problem &problem) |
|
◆ SymmetricPointToPlaneError()
optimization_common::SymmetricPointToPlaneError::SymmetricPointToPlaneError |
( |
const Eigen::Vector3d & |
source_t_point, |
|
|
const Eigen::Vector3d & |
target_t_point, |
|
|
const Eigen::Vector3d & |
source_normal, |
|
|
const Eigen::Vector3d & |
target_normal |
|
) |
| |
|
inline |
◆ AddCostFunction()
static void optimization_common::SymmetricPointToPlaneError::AddCostFunction |
( |
const Eigen::Vector3d & |
source_t_point, |
|
|
const Eigen::Vector3d & |
target_t_point, |
|
|
const Eigen::Vector3d & |
source_normal, |
|
|
const Eigen::Vector3d & |
target_normal, |
|
|
Eigen::Matrix< double, 6, 1 > & |
target_T_source, |
|
|
ceres::Problem & |
problem |
|
) |
| |
|
inlinestatic |
◆ operator()()
template<typename T >
bool optimization_common::SymmetricPointToPlaneError::operator() |
( |
const T * |
target_T_source_data, |
|
|
T * |
symmetric_point_to_plane_error |
|
) |
| const |
|
inline |
The documentation for this class was generated from the following file:
- localization/optimization_common/include/optimization_common/residuals.h