44 #ifndef EDGE_ACCELERATION_H_ 45 #define EDGE_ACCELERATION_H_ 53 #include <geometry_msgs/Twist.h> 106 double dist1 = diff1.norm();
107 double dist2 = diff2.norm();
108 const double angle_diff1 = g2o::normalize_theta(pose2->
theta() - pose1->
theta());
109 const double angle_diff2 = g2o::normalize_theta(pose3->
theta() - pose2->
theta());
113 if (angle_diff1 != 0)
115 const double radius = dist1/(2*
sin(angle_diff1/2));
116 dist1 = fabs( angle_diff1 * radius );
118 if (angle_diff2 != 0)
120 const double radius = dist2/(2*
sin(angle_diff2/2));
121 dist2 = fabs( angle_diff2 * radius );
125 double vel1 = dist1 / dt1->
dt();
126 double vel2 = dist2 / dt2->
dt();
135 const double acc_lin = (vel2 - vel1)*2 / ( dt1->
dt() + dt2->
dt() );
141 const double omega1 = angle_diff1 / dt1->
dt();
142 const double omega2 = angle_diff2 / dt2->
dt();
143 const double acc_rot = (omega2 - omega1)*2 / ( dt1->
dt() + dt2->
dt() );
148 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]);
149 ROS_ASSERT_MSG(std::isfinite(_error[1]),
"EdgeAcceleration::computeError() rotational: _error[1]=%f\n",_error[1]);
154 #ifdef USE_ANALYTIC_JACOBI 159 void linearizeOplus()
162 const VertexPointXY* conf1 =
static_cast<const VertexPointXY*
>(_vertices[0]);
163 const VertexPointXY* conf2 =
static_cast<const VertexPointXY*
>(_vertices[1]);
164 const VertexPointXY* conf3 =
static_cast<const VertexPointXY*
>(_vertices[2]);
167 const VertexOrientation* angle1 =
static_cast<const VertexOrientation*
>(_vertices[5]);
168 const VertexOrientation* angle2 =
static_cast<const VertexOrientation*
>(_vertices[6]);
169 const VertexOrientation* angle3 =
static_cast<const VertexOrientation*
>(_vertices[7]);
171 Eigen::Vector2d deltaS1 = conf2->estimate() - conf1->estimate();
172 Eigen::Vector2d deltaS2 = conf3->estimate() - conf2->estimate();
173 double dist1 = deltaS1.norm();
174 double dist2 = deltaS2.norm();
176 double sum_time = deltaT1->estimate() + deltaT2->estimate();
177 double sum_time_inv = 1 / sum_time;
178 double dt1_inv = 1/deltaT1->estimate();
179 double dt2_inv = 1/deltaT2->estimate();
180 double aux0 = 2/sum_time_inv;
181 double aux1 = dist1 * deltaT1->estimate();
182 double aux2 = dist2 * deltaT2->estimate();
184 double vel1 = dist1 * dt1_inv;
185 double vel2 = dist2 * dt2_inv;
186 double omega1 = g2o::normalize_theta( angle2->estimate() - angle1->estimate() ) * dt1_inv;
187 double omega2 = g2o::normalize_theta( angle3->estimate() - angle2->estimate() ) * dt2_inv;
188 double acc = (vel2 - vel1) * aux0;
189 double omegadot = (omega2 - omega1) * aux0;
190 double aux3 = -acc/2;
191 double aux4 = -omegadot/2;
193 double dev_border_acc =
penaltyBoundToIntervalDerivative(acc, tebConfig.robot_acceleration_max_trans,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order);
194 double dev_border_omegadot =
penaltyBoundToIntervalDerivative(omegadot, tebConfig.robot_acceleration_max_rot,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order);
196 _jacobianOplus[0].resize(2,2);
197 _jacobianOplus[1].resize(2,2);
198 _jacobianOplus[2].resize(2,2);
199 _jacobianOplus[3].resize(2,1);
200 _jacobianOplus[4].resize(2,1);
201 _jacobianOplus[5].resize(2,1);
202 _jacobianOplus[6].resize(2,1);
203 _jacobianOplus[7].resize(2,1);
205 if (aux1==0) aux1=1e-20;
206 if (aux2==0) aux2=1e-20;
208 if (dev_border_acc!=0)
212 _jacobianOplus[0](0,0) = aux0 * deltaS1[0] / aux1 * dev_border_acc;
213 _jacobianOplus[0](0,1) = aux0 * deltaS1[1] / aux1 * dev_border_acc;
214 _jacobianOplus[1](0,0) = -aux0 * ( deltaS1[0] / aux1 + deltaS2[0] / aux2 ) * dev_border_acc;
215 _jacobianOplus[1](0,1) = -aux0 * ( deltaS1[1] / aux1 + deltaS2[1] / aux2 ) * dev_border_acc;
216 _jacobianOplus[2](0,0) = aux0 * deltaS2[0] / aux2 * dev_border_acc;
217 _jacobianOplus[2](0,1) = aux0 * deltaS2[1] / aux2 * dev_border_acc;
218 _jacobianOplus[2](0,0) = 0;
219 _jacobianOplus[2](0,1) = 0;
220 _jacobianOplus[3](0,0) = aux0 * (aux3 + vel1 * dt1_inv) * dev_border_acc;
221 _jacobianOplus[4](0,0) = aux0 * (aux3 - vel2 * dt2_inv) * dev_border_acc;
225 _jacobianOplus[0](0,0) = 0;
226 _jacobianOplus[0](0,1) = 0;
227 _jacobianOplus[1](0,0) = 0;
228 _jacobianOplus[1](0,1) = 0;
229 _jacobianOplus[2](0,0) = 0;
230 _jacobianOplus[2](0,1) = 0;
231 _jacobianOplus[3](0,0) = 0;
232 _jacobianOplus[4](0,0) = 0;
235 if (dev_border_omegadot!=0)
237 _jacobianOplus[3](1,0) = aux0 * ( aux4 + omega1 * dt1_inv ) * dev_border_omegadot;
238 _jacobianOplus[4](1,0) = aux0 * ( aux4 - omega2 * dt2_inv ) * dev_border_omegadot;
239 _jacobianOplus[5](1,0) = aux0 * dt1_inv * dev_border_omegadot;
240 _jacobianOplus[6](1,0) = -aux0 * ( dt1_inv + dt2_inv ) * dev_border_omegadot;
241 _jacobianOplus[7](1,0) = aux0 * dt2_inv * dev_border_omegadot;
245 _jacobianOplus[3](1,0) = 0;
246 _jacobianOplus[4](1,0) = 0;
247 _jacobianOplus[5](1,0) = 0;
248 _jacobianOplus[6](1,0) = 0;
249 _jacobianOplus[7](1,0) = 0;
252 _jacobianOplus[0](1,0) = 0;
253 _jacobianOplus[0](1,1) = 0;
254 _jacobianOplus[1](1,0) = 0;
255 _jacobianOplus[1](1,1) = 0;
256 _jacobianOplus[2](1,0) = 0;
257 _jacobianOplus[2](1,1) = 0;
258 _jacobianOplus[5](0,0) = 0;
259 _jacobianOplus[6](0,0) = 0;
260 _jacobianOplus[7](0,0) = 0;
267 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
310 ROS_ASSERT_MSG(
cfg_ && _measurement,
"You must call setTebConfig() and setStartVelocity() on EdgeAccelerationStart()");
317 double dist = diff.norm();
318 const double angle_diff = g2o::normalize_theta(pose2->
theta() - pose1->
theta());
321 const double radius = dist/(2*
sin(angle_diff/2));
322 dist = fabs( angle_diff * radius );
325 const double vel1 = _measurement->linear.x;
326 double vel2 = dist / dt->
dt();
332 const double acc_lin = (vel2 - vel1) / dt->
dt();
337 const double omega1 = _measurement->angular.z;
338 const double omega2 = angle_diff / dt->
dt();
339 const double acc_rot = (omega2 - omega1) / dt->
dt();
343 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeAccelerationStart::computeError() translational: _error[0]=%f\n",_error[0]);
344 ROS_ASSERT_MSG(std::isfinite(_error[1]),
"EdgeAccelerationStart::computeError() rotational: _error[1]=%f\n",_error[1]);
353 _measurement = &vel_start;
357 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
401 ROS_ASSERT_MSG(
cfg_ && _measurement,
"You must call setTebConfig() and setGoalVelocity() on EdgeAccelerationGoal()");
409 double dist = diff.norm();
410 const double angle_diff = g2o::normalize_theta(pose_goal->
theta() - pose_pre_goal->
theta());
413 double radius = dist/(2*
sin(angle_diff/2));
414 dist = fabs( angle_diff * radius );
417 double vel1 = dist / dt->
dt();
418 const double vel2 = _measurement->linear.x;
424 const double acc_lin = (vel2 - vel1) / dt->
dt();
429 const double omega1 = angle_diff / dt->
dt();
430 const double omega2 = _measurement->angular.z;
431 const double acc_rot = (omega2 - omega1) / dt->
dt();
435 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeAccelerationGoal::computeError() translational: _error[0]=%f\n",_error[0]);
436 ROS_ASSERT_MSG(std::isfinite(_error[1]),
"EdgeAccelerationGoal::computeError() rotational: _error[1]=%f\n",_error[1]);
445 _measurement = &vel_goal;
449 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
502 double cos_theta1 = std::cos(pose1->
theta());
503 double sin_theta1 = std::sin(pose1->
theta());
504 double cos_theta2 = std::cos(pose2->
theta());
505 double sin_theta2 = std::sin(pose2->
theta());
508 double p1_dx = cos_theta1*diff1.x() + sin_theta1*diff1.y();
509 double p1_dy = -sin_theta1*diff1.x() + cos_theta1*diff1.y();
511 double p2_dx = cos_theta2*diff2.x() + sin_theta2*diff2.y();
512 double p2_dy = -sin_theta2*diff2.x() + cos_theta2*diff2.y();
514 double vel1_x = p1_dx / dt1->
dt();
515 double vel1_y = p1_dy / dt1->
dt();
516 double vel2_x = p2_dx / dt2->
dt();
517 double vel2_y = p2_dy / dt2->
dt();
519 double dt12 = dt1->
dt() + dt2->
dt();
521 double acc_x = (vel2_x - vel1_x)*2 / dt12;
522 double acc_y = (vel2_y - vel1_y)*2 / dt12;
528 double omega1 = g2o::normalize_theta(pose2->
theta() - pose1->
theta()) / dt1->
dt();
529 double omega2 = g2o::normalize_theta(pose3->
theta() - pose2->
theta()) / dt2->
dt();
530 double acc_rot = (omega2 - omega1)*2 / dt12;
535 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]);
536 ROS_ASSERT_MSG(std::isfinite(_error[1]),
"EdgeAcceleration::computeError() strafing: _error[1]=%f\n",_error[1]);
537 ROS_ASSERT_MSG(std::isfinite(_error[2]),
"EdgeAcceleration::computeError() rotational: _error[2]=%f\n",_error[2]);
541 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
584 ROS_ASSERT_MSG(
cfg_ && _measurement,
"You must call setTebConfig() and setStartVelocity() on EdgeAccelerationStart()");
592 double cos_theta1 = std::cos(pose1->
theta());
593 double sin_theta1 = std::sin(pose1->
theta());
596 double p1_dx = cos_theta1*diff.x() + sin_theta1*diff.y();
597 double p1_dy = -sin_theta1*diff.x() + cos_theta1*diff.y();
599 double vel1_x = _measurement->linear.x;
600 double vel1_y = _measurement->linear.y;
601 double vel2_x = p1_dx / dt->
dt();
602 double vel2_y = p1_dy / dt->
dt();
604 double acc_lin_x = (vel2_x - vel1_x) / dt->
dt();
605 double acc_lin_y = (vel2_y - vel1_y) / dt->
dt();
611 double omega1 = _measurement->angular.z;
612 double omega2 = g2o::normalize_theta(pose2->
theta() - pose1->
theta()) / dt->
dt();
613 double acc_rot = (omega2 - omega1) / dt->
dt();
617 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeAccelerationStart::computeError() translational: _error[0]=%f\n",_error[0]);
618 ROS_ASSERT_MSG(std::isfinite(_error[1]),
"EdgeAccelerationStart::computeError() strafing: _error[1]=%f\n",_error[1]);
619 ROS_ASSERT_MSG(std::isfinite(_error[2]),
"EdgeAccelerationStart::computeError() rotational: _error[2]=%f\n",_error[2]);
628 _measurement = &vel_start;
632 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
675 ROS_ASSERT_MSG(
cfg_ && _measurement,
"You must call setTebConfig() and setGoalVelocity() on EdgeAccelerationGoal()");
684 double cos_theta1 = std::cos(pose_pre_goal->
theta());
685 double sin_theta1 = std::sin(pose_pre_goal->
theta());
688 double p1_dx = cos_theta1*diff.x() + sin_theta1*diff.y();
689 double p1_dy = -sin_theta1*diff.x() + cos_theta1*diff.y();
691 double vel1_x = p1_dx / dt->
dt();
692 double vel1_y = p1_dy / dt->
dt();
693 double vel2_x = _measurement->linear.x;
694 double vel2_y = _measurement->linear.y;
696 double acc_lin_x = (vel2_x - vel1_x) / dt->
dt();
697 double acc_lin_y = (vel2_y - vel1_y) / dt->
dt();
703 double omega1 = g2o::normalize_theta(pose_goal->
theta() - pose_pre_goal->
theta()) / dt->
dt();
704 double omega2 = _measurement->angular.z;
705 double acc_rot = (omega2 - omega1) / dt->
dt();
709 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeAccelerationGoal::computeError() translational: _error[0]=%f\n",_error[0]);
710 ROS_ASSERT_MSG(std::isfinite(_error[1]),
"EdgeAccelerationGoal::computeError() strafing: _error[1]=%f\n",_error[1]);
711 ROS_ASSERT_MSG(std::isfinite(_error[2]),
"EdgeAccelerationGoal::computeError() rotational: _error[2]=%f\n",_error[2]);
721 _measurement = &vel_goal;
726 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Edge defining the cost function for limiting the translational and rotational acceleration at the end...
virtual void resize(size_t size)
EdgeAccelerationHolonomicStart()
Construct edge.
double penaltyBoundToInterval(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var to the interval .
EdgeAccelerationStart()
Construct edge.
void computeError()
Actual cost function.
double acc_lim_x
Maximum translational acceleration of the robot.
Edge defining the cost function for limiting the translational and rotational acceleration at the end...
void computeError()
Actual cost function.
void setInitialVelocity(const geometry_msgs::Twist &vel_start)
Set the initial velocity that is taken into account for calculating the acceleration.
Edge defining the cost function for limiting the translational and rotational acceleration.
Edge defining the cost function for limiting the translational and rotational acceleration at the beg...
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
double fast_sigmoid(double x)
Calculate a fast approximation of a sigmoid function.
void setInitialVelocity(const geometry_msgs::Twist &vel_start)
Set the initial velocity that is taken into account for calculating the acceleration.
Edge defining the cost function for limiting the translational and rotational acceleration.
EdgeAccelerationGoal()
Construct edge.
void computeError()
Actual cost function.
void setGoalVelocity(const geometry_msgs::Twist &vel_goal)
Set the goal / final velocity that is taken into account for calculating the acceleration.
double acc_lim_theta
Maximum angular acceleration of the robot.
double & theta()
Access the orientation part (yaw angle) of the pose.
Base edge connecting two vertices in the TEB optimization problem.
#define ROS_ASSERT_MSG(cond,...)
double penaltyBoundToIntervalDerivative(const double &var, const double &a, const double &epsilon)
Derivative of the linear penalty function for bounding var to the interval .
Edge defining the cost function for limiting the translational and rotational acceleration at the beg...
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
Eigen::Vector2d & position()
Access the 2D position part.
const TebConfig * cfg_
Store TebConfig class for parameters.
double & dt()
Access the timediff value of the vertex.
void setGoalVelocity(const geometry_msgs::Twist &vel_goal)
Set the goal / final velocity that is taken into account for calculating the acceleration.
void computeError()
Actual cost function.
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
void computeError()
Actual cost function.
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
EdgeAccelerationHolonomic()
Construct edge.
double acc_lim_y
Maximum strafing acceleration of the robot.
EdgeAccelerationHolonomicGoal()
Construct edge.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void computeError()
Actual cost function.
EdgeAcceleration()
Construct edge.
This class stores and wraps a time difference into a vertex that can be optimized via g2o...