00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044 #ifndef EDGE_VELOCITY_H
00045 #define EDGE_VELOCITY_H
00046
00047 #include <teb_local_planner/g2o_types/vertex_pose.h>
00048 #include <teb_local_planner/g2o_types/vertex_timediff.h>
00049 #include <teb_local_planner/g2o_types/base_teb_edges.h>
00050 #include <teb_local_planner/g2o_types/penalties.h>
00051 #include <teb_local_planner/teb_config.h>
00052
00053
00054 #include <iostream>
00055
00056 namespace teb_local_planner
00057 {
00058
00059
00075 class EdgeVelocity : public BaseTebMultiEdge<2, double>
00076 {
00077 public:
00078
00082 EdgeVelocity()
00083 {
00084 this->resize(3);
00085 }
00086
00090 void computeError()
00091 {
00092 ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocity()");
00093 const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00094 const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00095 const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
00096
00097 const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position();
00098
00099 double dist = deltaS.norm();
00100 const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta());
00101 if (cfg_->trajectory.exact_arc_length && angle_diff != 0)
00102 {
00103 double radius = dist/(2*sin(angle_diff/2));
00104 dist = fabs( angle_diff * radius );
00105 }
00106 double vel = dist / deltaT->estimate();
00107
00108
00109 vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) );
00110
00111 const double omega = angle_diff / deltaT->estimate();
00112
00113 _error[0] = penaltyBoundToInterval(vel, -cfg_->robot.max_vel_x_backwards, cfg_->robot.max_vel_x,cfg_->optim.penalty_epsilon);
00114 _error[1] = penaltyBoundToInterval(omega, cfg_->robot.max_vel_theta,cfg_->optim.penalty_epsilon);
00115
00116 ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeVelocity::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
00117 }
00118
00119 #ifdef USE_ANALYTIC_JACOBI
00120 #if 0 //TODO the hardcoded jacobian does not include the changing direction (just the absolute value)
00121
00122
00126 void linearizeOplus()
00127 {
00128 ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocity()");
00129 const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00130 const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00131 const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
00132
00133 Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00134 double dist = deltaS.norm();
00135 double aux1 = dist*deltaT->estimate();
00136 double aux2 = 1/deltaT->estimate();
00137
00138 double vel = dist * aux2;
00139 double omega = g2o::normalize_theta(conf2->theta() - conf1->theta()) * aux2;
00140
00141 double dev_border_vel = penaltyBoundToIntervalDerivative(vel, -cfg_->robot.max_vel_x_backwards, cfg_->robot.max_vel_x,cfg_->optim.penalty_epsilon);
00142 double dev_border_omega = penaltyBoundToIntervalDerivative(omega, cfg_->robot.max_vel_theta,cfg_->optim.penalty_epsilon);
00143
00144 _jacobianOplus[0].resize(2,3);
00145 _jacobianOplus[1].resize(2,3);
00146 _jacobianOplus[2].resize(2,1);
00147
00148
00149
00150
00151 if (dev_border_vel!=0)
00152 {
00153 double aux3 = dev_border_vel / aux1;
00154 _jacobianOplus[0](0,0) = -deltaS[0] * aux3;
00155 _jacobianOplus[0](0,1) = -deltaS[1] * aux3;
00156 _jacobianOplus[1](0,0) = deltaS[0] * aux3;
00157 _jacobianOplus[1](0,1) = deltaS[1] * aux3;
00158 _jacobianOplus[2](0,0) = -vel * aux2 * dev_border_vel;
00159 }
00160 else
00161 {
00162 _jacobianOplus[0](0,0) = 0;
00163 _jacobianOplus[0](0,1) = 0;
00164 _jacobianOplus[1](0,0) = 0;
00165 _jacobianOplus[1](0,1) = 0;
00166 _jacobianOplus[2](0,0) = 0;
00167 }
00168
00169 if (dev_border_omega!=0)
00170 {
00171 double aux4 = aux2 * dev_border_omega;
00172 _jacobianOplus[2](1,0) = -omega * aux4;
00173 _jacobianOplus[0](1,2) = -aux4;
00174 _jacobianOplus[1](1,2) = aux4;
00175 }
00176 else
00177 {
00178 _jacobianOplus[2](1,0) = 0;
00179 _jacobianOplus[0](1,2) = 0;
00180 _jacobianOplus[1](1,2) = 0;
00181 }
00182
00183 _jacobianOplus[0](1,0) = 0;
00184 _jacobianOplus[0](1,1) = 0;
00185 _jacobianOplus[1](1,0) = 0;
00186 _jacobianOplus[1](1,1) = 0;
00187 _jacobianOplus[0](0,2) = 0;
00188 _jacobianOplus[1](0,2) = 0;
00189 }
00190 #endif
00191 #endif
00192
00193
00194 public:
00195
00196 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00197
00198 };
00199
00200
00201
00202
00203
00204
00221 class EdgeVelocityHolonomic : public BaseTebMultiEdge<3, double>
00222 {
00223 public:
00224
00228 EdgeVelocityHolonomic()
00229 {
00230 this->resize(3);
00231 }
00232
00236 void computeError()
00237 {
00238 ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocityHolonomic()");
00239 const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
00240 const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
00241 const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
00242 Eigen::Vector2d deltaS = conf2->position() - conf1->position();
00243
00244 double cos_theta1 = std::cos(conf1->theta());
00245 double sin_theta1 = std::sin(conf1->theta());
00246
00247
00248 double r_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
00249 double r_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
00250
00251 double vx = r_dx / deltaT->estimate();
00252 double vy = r_dy / deltaT->estimate();
00253 double omega = g2o::normalize_theta(conf2->theta() - conf1->theta()) / deltaT->estimate();
00254
00255 _error[0] = penaltyBoundToInterval(vx, -cfg_->robot.max_vel_x_backwards, cfg_->robot.max_vel_x, cfg_->optim.penalty_epsilon);
00256 _error[1] = penaltyBoundToInterval(vy, cfg_->robot.max_vel_y, 0.0);
00257 _error[2] = penaltyBoundToInterval(omega, cfg_->robot.max_vel_theta,cfg_->optim.penalty_epsilon);
00258
00259 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]) && std::isfinite(_error[2]),
00260 "EdgeVelocityHolonomic::computeError() _error[0]=%f _error[1]=%f _error[2]=%f\n",_error[0],_error[1],_error[2]);
00261 }
00262
00263
00264 public:
00265
00266 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00267
00268 };
00269
00270
00271 }
00272
00273 #endif