44 #ifndef EDGE_VELOCITY_H 45 #define EDGE_VELOCITY_H 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();
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
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();
259 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]) && std::isfinite(_error[2]),
260 "EdgeVelocityHolonomic::computeError() _error[0]=%f _error[1]=%f _error[2]=%f\n",_error[0],_error[1],_error[2]);
266 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual void resize(size_t size)
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) ...
double penaltyBoundToInterval(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var to the interval .
void computeError()
Actual cost function.
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
Edge defining the cost function for limiting the translational and rotational velocity.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
double fast_sigmoid(double x)
Calculate a fast approximation of a sigmoid function.
void computeError()
Actual cost function.
Edge defining the cost function for limiting the translational and rotational velocity according to x...
double & theta()
Access the orientation part (yaw angle) of the pose.
Base edge connecting two vertices in the TEB optimization problem.
EdgeVelocityHolonomic()
Construct edge.
#define ROS_ASSERT_MSG(cond,...)
double max_vel_theta
Maximum angular velocity of the robot.
double penaltyBoundToIntervalDerivative(const double &var, const double &a, const double &epsilon)
Derivative of the linear penalty function for bounding var to the interval .
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...
EdgeVelocity()
Construct edge.
Eigen::Vector2d & position()
Access the 2D position part.
const TebConfig * cfg_
Store TebConfig class for parameters.
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
double max_vel_x
Maximum translational velocity of the robot.
This class stores and wraps a time difference into a vertex that can be optimized via g2o...