Go to the documentation of this file.
33 #ifndef CERES_EXAMPLES_POSE_GRAPH_2D_POSE_GRAPH_2D_ERROR_TERM_H_
34 #define CERES_EXAMPLES_POSE_GRAPH_2D_POSE_GRAPH_2D_ERROR_TERM_H_
47 rotation << cos_yaw, -sin_yaw, sin_yaw, cos_yaw;
63 const Eigen::Matrix3d& sqrt_information)
69 bool operator()(
const T*
const x_a,
const T*
const y_a,
const T*
const yaw_a,
70 const T*
const x_b,
const T*
const y_b,
const T*
const yaw_b,
71 T* residuals_ptr)
const {
77 residuals_map.template head<2>() =
90 static ceres::CostFunction*
Create(
double x_ab,
double y_ab,
91 double yaw_ab_radians,
92 const Eigen::Matrix3d& sqrt_information) {
95 x_ab, y_ab, yaw_ab_radians, sqrt_information)));
112 #endif // CERES_EXAMPLES_POSE_GRAPH_2D_POSE_GRAPH_2D_ERROR_TERM_H_
T NormalizeAngle(const T &angle_radians)
bool operator()(const T *const x_a, const T *const y_a, const T *const yaw_a, const T *const x_b, const T *const y_b, const T *const yaw_b, T *residuals_ptr) const
Jet< T, N > sin(const Jet< T, N > &f)
const double yaw_ab_radians_
const Eigen::Matrix3d sqrt_information_
static ceres::CostFunction * Create(double x_ab, double y_ab, double yaw_ab_radians, const Eigen::Matrix3d &sqrt_information)
PoseGraph2dErrorTerm(double x_ab, double y_ab, double yaw_ab_radians, const Eigen::Matrix3d &sqrt_information)
Jet< T, N > cos(const Jet< T, N > &f)
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
const Eigen::Vector2d p_ab_
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
Eigen::Matrix< T, 2, 2 > RotationMatrix2D(T yaw_radians)
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:14