43 #ifndef EDGE_OBSTACLE_H_
44 #define EDGE_OBSTACLE_H_
70 class EdgeObstacle :
public BaseTebUnaryEdge<1, const Obstacle*, VertexPose>
87 ROS_ASSERT_MSG(
cfg_ && _measurement,
"You must call setTebConfig() and setObstacle() on EdgeObstacle()");
88 const VertexPose* bandpt =
static_cast<const VertexPose*
>(_vertices[0]);
90 double dist =
cfg_->
robot_model->calculateDistance(bandpt->pose(), _measurement);
105 ROS_ASSERT_MSG(std::isfinite(_error[0]),
"EdgeObstacle::computeError() _error[0]=%f\n",_error[0]);
108 #ifdef USE_ANALYTIC_JACOBI
114 void linearizeOplus()
117 const VertexPose* bandpt =
static_cast<const VertexPose*
>(_vertices[0]);
119 Eigen::Vector2d deltaS = *_measurement - bandpt->position();
120 double angdiff = atan2(deltaS[1],deltaS[0])-bandpt->theta();
122 double dist_squared = deltaS.squaredNorm();
123 double dist = sqrt(dist_squared);
125 double aux0 = sin(angdiff);
128 if (dev_left_border==0)
130 _jacobianOplusXi( 0 , 0 ) = 0;
131 _jacobianOplusXi( 0 , 1 ) = 0;
132 _jacobianOplusXi( 0 , 2 ) = 0;
136 double aux1 = -fabs(aux0) / dist;
137 double dev_norm_x = deltaS[0]*aux1;
138 double dev_norm_y = deltaS[1]*aux1;
140 double aux2 = cos(angdiff) * g2o::sign(aux0);
141 double aux3 = aux2 / dist_squared;
142 double dev_proj_x = aux3 * deltaS[1] * dist;
143 double dev_proj_y = -aux3 * deltaS[0] * dist;
144 double dev_proj_angle = -aux2;
146 _jacobianOplusXi( 0 , 0 ) = dev_left_border * ( dev_norm_x + dev_proj_x );
147 _jacobianOplusXi( 0 , 1 ) = dev_left_border * ( dev_norm_y + dev_proj_y );
148 _jacobianOplusXi( 0 , 2 ) = dev_left_border * dev_proj_angle;
159 _measurement = obstacle;
167 void setParameters(
const TebConfig& cfg,
const Obstacle* obstacle)
170 _measurement = obstacle;
173 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
192 class EdgeInflatedObstacle :
public BaseTebUnaryEdge<2, const Obstacle*, VertexPose>
209 ROS_ASSERT_MSG(
cfg_ && _measurement,
"You must call setTebConfig() and setObstacle() on EdgeInflatedObstacle()");
232 ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]),
"EdgeInflatedObstacle::computeError() _error[0]=%f, _error[1]=%f\n",_error[0], _error[1]);
241 _measurement = obstacle;
252 _measurement = obstacle;
255 EIGEN_MAKE_ALIGNED_OPERATOR_NEW