edge_velocity.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Notes:
37  * The following class is derived from a class defined by the
38  * g2o-framework. g2o is licensed under the terms of the BSD License.
39  * Refer to the base class source for detailed licensing information.
40  *
41  * Author: Christoph Rösmann
42  *********************************************************************/
43 
44 #ifndef EDGE_VELOCITY_H
45 #define EDGE_VELOCITY_H
46 
52 
53 
54 #include <iostream>
55 
56 namespace teb_local_planner
57 {
58 
59 
75 class EdgeVelocity : public BaseTebMultiEdge<2, double>
76 {
77 public:
78 
82  EdgeVelocity()
83  {
84  this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices
85  }
86 
90  void computeError()
91  {
92  ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocity()");
93  const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
94  const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
95  const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
96 
97  const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position();
98 
99  double dist = deltaS.norm();
100  const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta());
101  if (cfg_->trajectory.exact_arc_length && angle_diff != 0)
102  {
103  double radius = dist/(2*sin(angle_diff/2));
104  dist = fabs( angle_diff * radius ); // actual arg length!
105  }
106  double vel = dist / deltaT->estimate();
107 
108 // vel *= g2o::sign(deltaS[0]*cos(conf1->theta()) + deltaS[1]*sin(conf1->theta())); // consider direction
109  vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction
110 
111  const double omega = angle_diff / deltaT->estimate();
112 
115 
116  ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeVelocity::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);
117  }
118 
119 #ifdef USE_ANALYTIC_JACOBI
120 #if 0 //TODO the hardcoded jacobian does not include the changing direction (just the absolute value)
121  // Change accordingly...
122 
126  void linearizeOplus()
127  {
128  ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocity()");
129  const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
130  const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
131  const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
132 
133  Eigen::Vector2d deltaS = conf2->position() - conf1->position();
134  double dist = deltaS.norm();
135  double aux1 = dist*deltaT->estimate();
136  double aux2 = 1/deltaT->estimate();
137 
138  double vel = dist * aux2;
139  double omega = g2o::normalize_theta(conf2->theta() - conf1->theta()) * aux2;
140 
143 
144  _jacobianOplus[0].resize(2,3); // conf1
145  _jacobianOplus[1].resize(2,3); // conf2
146  _jacobianOplus[2].resize(2,1); // deltaT
147 
148 // if (aux1==0) aux1=1e-6;
149 // if (aux2==0) aux2=1e-6;
150 
151  if (dev_border_vel!=0)
152  {
153  double aux3 = dev_border_vel / aux1;
154  _jacobianOplus[0](0,0) = -deltaS[0] * aux3; // vel x1
155  _jacobianOplus[0](0,1) = -deltaS[1] * aux3; // vel y1
156  _jacobianOplus[1](0,0) = deltaS[0] * aux3; // vel x2
157  _jacobianOplus[1](0,1) = deltaS[1] * aux3; // vel y2
158  _jacobianOplus[2](0,0) = -vel * aux2 * dev_border_vel; // vel deltaT
159  }
160  else
161  {
162  _jacobianOplus[0](0,0) = 0; // vel x1
163  _jacobianOplus[0](0,1) = 0; // vel y1
164  _jacobianOplus[1](0,0) = 0; // vel x2
165  _jacobianOplus[1](0,1) = 0; // vel y2
166  _jacobianOplus[2](0,0) = 0; // vel deltaT
167  }
168 
169  if (dev_border_omega!=0)
170  {
171  double aux4 = aux2 * dev_border_omega;
172  _jacobianOplus[2](1,0) = -omega * aux4; // omega deltaT
173  _jacobianOplus[0](1,2) = -aux4; // omega angle1
174  _jacobianOplus[1](1,2) = aux4; // omega angle2
175  }
176  else
177  {
178  _jacobianOplus[2](1,0) = 0; // omega deltaT
179  _jacobianOplus[0](1,2) = 0; // omega angle1
180  _jacobianOplus[1](1,2) = 0; // omega angle2
181  }
182 
183  _jacobianOplus[0](1,0) = 0; // omega x1
184  _jacobianOplus[0](1,1) = 0; // omega y1
185  _jacobianOplus[1](1,0) = 0; // omega x2
186  _jacobianOplus[1](1,1) = 0; // omega y2
187  _jacobianOplus[0](0,2) = 0; // vel angle1
188  _jacobianOplus[1](0,2) = 0; // vel angle2
189  }
190 #endif
191 #endif
192 
193 
194 public:
195 
196  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
197 
198 };
199 
200 
201 
202 
203 
204 
221 class EdgeVelocityHolonomic : public BaseTebMultiEdge<3, double>
222 {
223 public:
224 
229  {
230  this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices
231  }
232 
236  void computeError()
237  {
238  ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocityHolonomic()");
239  const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
240  const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
241  const VertexTimeDiff* deltaT = static_cast<const VertexTimeDiff*>(_vertices[2]);
242  Eigen::Vector2d deltaS = conf2->position() - conf1->position();
243 
244  double cos_theta1 = std::cos(conf1->theta());
245  double sin_theta1 = std::sin(conf1->theta());
246 
247  // transform conf2 into current robot frame conf1 (inverse 2d rotation matrix)
248  double r_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
249  double r_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
250 
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();
254 
255 
256  double max_vel_trans_remaining_y;
257  double max_vel_trans_remaining_x;
258  max_vel_trans_remaining_y = std::sqrt(std::max(0.0, cfg_->robot.max_vel_trans * cfg_->robot.max_vel_trans - vx * vx));
259  max_vel_trans_remaining_x = std::sqrt(std::max(0.0, cfg_->robot.max_vel_trans * cfg_->robot.max_vel_trans - vy * vy));
260 
261  double max_vel_y = std::min(max_vel_trans_remaining_y, cfg_->robot.max_vel_y);
262  double max_vel_x = std::min(max_vel_trans_remaining_x, cfg_->robot.max_vel_x);
263  double max_vel_x_backwards = std::min(max_vel_trans_remaining_x, cfg_->robot.max_vel_x_backwards);
264 
265  // we do not apply the penalty epsilon for linear velocities on
266  // holonomic robots, since either vx or yy could be close to zero
267  _error[0] = penaltyBoundToInterval(vx, -max_vel_x_backwards, max_vel_x, 0.0);
268  _error[1] = penaltyBoundToInterval(vy, max_vel_y, 0.0);
270 
271  ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]) && std::isfinite(_error[2]),
272  "EdgeVelocityHolonomic::computeError() _error[0]=%f _error[1]=%f _error[2]=%f\n",_error[0],_error[1],_error[2]);
273  }
274 
275 
276 public:
277 
278  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
279 
280 };
281 
282 
283 } // end namespace
284 
285 #endif
teb_local_planner::VertexPose::theta
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: vertex_pose.h:214
teb_local_planner::EdgeVelocityHolonomic::computeError
void computeError()
Actual cost function.
Definition: edge_velocity.h:277
teb_local_planner::TebConfig::Robot::max_vel_y
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!)
Definition: teb_config.h:101
teb_local_planner::TebConfig::Trajectory::exact_arc_length
bool exact_arc_length
If true, the planner uses the exact arc length in velocity, acceleration and turning rate computation...
Definition: teb_config.h:85
teb_local_planner::TebConfig::Robot::max_vel_trans
double max_vel_trans
Maximum translational velocity of the robot for omni robots, which is different from max_vel_x.
Definition: teb_config.h:102
teb_local_planner::TebConfig::Optimization::penalty_epsilon
double penalty_epsilon
Add a small safety margin to penalty functions for hard-constraint approximations.
Definition: teb_config.h:157
teb_local_planner::penaltyBoundToInterval
double penaltyBoundToInterval(const double &var, const double &a, const double &epsilon)
Linear penalty function for bounding var to the interval .
Definition: penalties.h:93
teb_local_planner::EdgeVelocity::EdgeVelocity
EdgeVelocity()
Construct edge.
Definition: edge_velocity.h:123
teb_local_planner::fast_sigmoid
double fast_sigmoid(double x)
Calculate a fast approximation of a sigmoid function.
Definition: misc.h:131
teb_local_planner::TebConfig::Robot::max_vel_x_backwards
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
Definition: teb_config.h:100
teb_local_planner::VertexTimeDiff
This class stores and wraps a time difference into a vertex that can be optimized via g2o.
Definition: vertex_timediff.h:102
teb_local_planner::EdgeVelocity::computeError
void computeError()
Actual cost function.
Definition: edge_velocity.h:131
teb_local_planner::TebConfig::trajectory
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
teb_config.h
penalties.h
teb_local_planner::TebConfig::robot
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
vertex_timediff.h
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
teb_local_planner::penaltyBoundToIntervalDerivative
double penaltyBoundToIntervalDerivative(const double &var, const double &a, const double &epsilon)
Derivative of the linear penalty function for bounding var to the interval .
Definition: penalties.h:163
teb_local_planner::EdgeVelocityHolonomic::EdgeVelocityHolonomic
EdgeVelocityHolonomic()
Construct edge.
Definition: edge_velocity.h:269
teb_local_planner::BaseTebMultiEdge< 2, double >::cfg_
const TebConfig * cfg_
Store TebConfig class for parameters.
Definition: base_teb_edges.h:306
teb_local_planner::TebConfig::Robot::max_vel_x
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:99
vertex_pose.h
teb_local_planner::BaseTebMultiEdge< 2, double >::resize
virtual void resize(size_t size)
Definition: base_teb_edges.h:254
base_teb_edges.h
teb_local_planner::VertexPose::position
Eigen::Vector2d & position()
Access the 2D position part.
Definition: vertex_pose.h:177
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::VertexPose
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
Definition: vertex_pose.h:104
teb_local_planner::TebConfig::optim
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
teb_local_planner::TebConfig::Robot::max_vel_theta
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:103


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15