44 #ifndef _EDGE_KINEMATICS_H 45 #define _EDGE_KINEMATICS_H 82 this->setMeasurement(0.);
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()
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;
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
191 this->setMeasurement(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
double penaltyBoundFromBelow(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var from below: .
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
EdgeKinematicsDiffDrive()
Construct edge.
double & theta()
Access the orientation part (yaw angle) of the pose.
void computeError()
Actual cost function.
#define ROS_ASSERT_MSG(cond,...)
const TebConfig * cfg_
Store TebConfig class for parameters.
double penaltyBoundFromBelowDerivative(const double &var, const double &a, const double &epsilon)
Derivative of the linear penalty function for bounding var from below: .
Base edge connecting two vertices in the TEB optimization problem.
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.
void computeError()
Actual cost function.
EdgeKinematicsCarlike()
Construct edge.
Edge defining the cost function for satisfying the non-holonomic kinematics of a carlike mobile robot...
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
Edge defining the cost function for satisfying the non-holonomic kinematics of a differential drive m...