44 #ifndef EDGE_VELOCITY_H
45 #define EDGE_VELOCITY_H
75 class EdgeVelocity :
public BaseTebMultiEdge<2, double>
93 const VertexPose* conf1 =
static_cast<const VertexPose*
>(_vertices[0]);
94 const VertexPose* conf2 =
static_cast<const VertexPose*
>(_vertices[1]);
95 const VertexTimeDiff* deltaT =
static_cast<const VertexTimeDiff*
>(_vertices[2]);
97 const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position();
99 double dist = deltaS.norm();
100 const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta());
103 double radius = dist/(2*sin(angle_diff/2));
104 dist = fabs( angle_diff * radius );
106 double vel = dist / deltaT->estimate();
109 vel *=
fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) );
111 const double omega = angle_diff / deltaT->estimate();
116 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeVelocity::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
119 #ifdef USE_ANALYTIC_JACOBI
120 #if 0 //TODO the hardcoded jacobian does not include the changing direction (just the absolute value)
126 void linearizeOplus()
134 double dist = deltaS.norm();
135 double aux1 = dist*deltaT->estimate();
136 double aux2 = 1/deltaT->estimate();
138 double vel = dist * aux2;
139 double omega = g2o::normalize_theta(conf2->
theta() - conf1->
theta()) * aux2;
144 _jacobianOplus[0].resize(2,3);
145 _jacobianOplus[1].resize(2,3);
146 _jacobianOplus[2].resize(2,1);
151 if (dev_border_vel!=0)
153 double aux3 = dev_border_vel / aux1;
154 _jacobianOplus[0](0,0) = -deltaS[0] * aux3;
155 _jacobianOplus[0](0,1) = -deltaS[1] * aux3;
156 _jacobianOplus[1](0,0) = deltaS[0] * aux3;
157 _jacobianOplus[1](0,1) = deltaS[1] * aux3;
158 _jacobianOplus[2](0,0) = -vel * aux2 * dev_border_vel;
162 _jacobianOplus[0](0,0) = 0;
163 _jacobianOplus[0](0,1) = 0;
164 _jacobianOplus[1](0,0) = 0;
165 _jacobianOplus[1](0,1) = 0;
166 _jacobianOplus[2](0,0) = 0;
169 if (dev_border_omega!=0)
171 double aux4 = aux2 * dev_border_omega;
172 _jacobianOplus[2](1,0) = -omega * aux4;
173 _jacobianOplus[0](1,2) = -aux4;
174 _jacobianOplus[1](1,2) = aux4;
178 _jacobianOplus[2](1,0) = 0;
179 _jacobianOplus[0](1,2) = 0;
180 _jacobianOplus[1](1,2) = 0;
183 _jacobianOplus[0](1,0) = 0;
184 _jacobianOplus[0](1,1) = 0;
185 _jacobianOplus[1](1,0) = 0;
186 _jacobianOplus[1](1,1) = 0;
187 _jacobianOplus[0](0,2) = 0;
188 _jacobianOplus[1](0,2) = 0;
196 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
221 class EdgeVelocityHolonomic :
public BaseTebMultiEdge<3, double>
239 const VertexPose* conf1 =
static_cast<const VertexPose*
>(_vertices[0]);
240 const VertexPose* conf2 =
static_cast<const VertexPose*
>(_vertices[1]);
241 const VertexTimeDiff* deltaT =
static_cast<const VertexTimeDiff*
>(_vertices[2]);
242 Eigen::Vector2d deltaS = conf2->position() - conf1->position();
244 double cos_theta1 = std::cos(conf1->theta());
245 double sin_theta1 = std::sin(conf1->theta());
248 double r_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
249 double r_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
251 double vx = r_dx / deltaT->estimate();
252 double vy = r_dy / deltaT->estimate();
253 double omega = g2o::normalize_theta(conf2->theta() - conf1->theta()) / deltaT->estimate();
256 double max_vel_trans_remaining_y;
257 double max_vel_trans_remaining_x;
271 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]) && std::isfinite(_error[2]),
272 "EdgeVelocityHolonomic::computeError() _error[0]=%f _error[1]=%f _error[2]=%f\n",_error[0],_error[1],_error[2]);
278 EIGEN_MAKE_ALIGNED_OPERATOR_NEW