44 #ifndef _EDGE_KINEMATICS_H
45 #define _EDGE_KINEMATICS_H
73 class EdgeKinematicsDiffDrive :
public BaseTebBinaryEdge<2, double, VertexPose, VertexPose>
82 this->setMeasurement(0.);
91 const VertexPose* conf1 =
static_cast<const VertexPose*
>(_vertices[0]);
92 const VertexPose* conf2 =
static_cast<const VertexPose*
>(_vertices[1]);
94 Eigen::Vector2d deltaS = conf2->position() - conf1->position();
97 _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
100 Eigen::Vector2d angle_vec ( cos(conf1->theta()), sin(conf1->theta()) );
104 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]),
"EdgeKinematicsDiffDrive::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
107 #ifdef USE_ANALYTIC_JACOBI
112 void linearizeOplus()
120 double cos1 = cos(conf1->
theta());
122 double sin1 = sin(conf1->
theta());
123 double sin2 = sin(conf2->
theta());
124 double aux1 = sin1 + sin2;
125 double aux2 = cos1 + cos2;
127 double dd_error_1 = deltaS[0]*cos1;
128 double dd_error_2 = deltaS[1]*sin1;
131 double dev_nh_abs = g2o::sign( ( cos(conf1->
theta())+cos(conf2->
theta()) ) * deltaS[1] -
132 ( sin(conf1->
theta())+sin(conf2->
theta()) ) * deltaS[0] );
135 _jacobianOplusXi(0,0) = aux1 * dev_nh_abs;
136 _jacobianOplusXi(0,1) = -aux2 * dev_nh_abs;
137 _jacobianOplusXi(1,0) = -cos1 * dd_dev;
138 _jacobianOplusXi(1,1) = -sin1 * dd_dev;
139 _jacobianOplusXi(0,2) = (-dd_error_2 - dd_error_1) * dev_nh_abs;
140 _jacobianOplusXi(1,2) = ( -sin1*deltaS[0] + cos1*deltaS[1] ) * dd_dev;
143 _jacobianOplusXj(0,0) = -aux1 * dev_nh_abs;
144 _jacobianOplusXj(0,1) = aux2 * dev_nh_abs;
145 _jacobianOplusXj(1,0) = cos1 * dd_dev;
146 _jacobianOplusXj(1,1) = sin1 * dd_dev;
147 _jacobianOplusXj(0,2) = (-sin2*deltaS[1] - cos2*deltaS[0]) * dev_nh_abs;
148 _jacobianOplusXj(1,2) = 0;
154 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
182 class EdgeKinematicsCarlike :
public BaseTebBinaryEdge<2, double, VertexPose, VertexPose>
191 this->setMeasurement(0.);
200 const VertexPose* conf1 =
static_cast<const VertexPose*
>(_vertices[0]);
201 const VertexPose* conf2 =
static_cast<const VertexPose*
>(_vertices[1]);
203 Eigen::Vector2d deltaS = conf2->
position() - conf1->position();
206 _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] );
209 double angle_diff = g2o::normalize_theta( conf2->theta() - conf1->theta() );
218 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]),
"EdgeKinematicsCarlike::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
222 EIGEN_MAKE_ALIGNED_OPERATOR_NEW