h_signature.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017,
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  * Authors: Christoph Rösmann, Franz Albers
37  *********************************************************************/
38 
39 #ifndef H_SIGNATURE_H_
40 #define H_SIGNATURE_H_
41 
43 #include <teb_local_planner/misc.h>
47 
48 #include <ros/ros.h>
49 #include <math.h>
50 #include <algorithm>
51 #include <functional>
52 #include <vector>
53 #include <iterator>
54 
55 
56 namespace teb_local_planner
57 {
58 
67 class HSignature : public EquivalenceClass
68 {
69 
70 public:
71 
76  HSignature(const TebConfig& cfg) : cfg_(&cfg) {}
77 
78 
96  template<typename BidirIter, typename Fun>
97  void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer* obstacles)
98  {
99  if (obstacles->empty())
100  {
101  hsignature_ = std::complex<double>(0,0);
102  return;
103  }
104 
105 
106  ROS_ASSERT_MSG(cfg_->hcp.h_signature_prescaler>0.1 && cfg_->hcp.h_signature_prescaler<=1, "Only a prescaler on the interval (0.1,1] ist allowed.");
107 
108  // guess values for f0
109  // paper proposes a+b=N-1 && |a-b|<=1, 1...N obstacles
110  int m = std::max( (int)obstacles->size()-1, 5 ); // for only a few obstacles we need a min threshold in order to get significantly high H-Signatures
111 
112  int a = (int) std::ceil(double(m)/2.0);
113  int b = m-a;
114 
115  std::advance(path_end, -1); // reduce path_end by 1 (since we check line segments between those path points
116 
117  typedef std::complex<long double> cplx;
118  // guess map size (only a really really coarse guess is required
119  // use distance from start to goal as distance to each direction
120  // TODO: one could move the map determination outside this function, since it remains constant for the whole planning interval
121  cplx start = fun_cplx_point(*path_start);
122  cplx end = fun_cplx_point(*path_end); // path_end points to the last point now after calling std::advance before
123  cplx delta = end-start;
124  cplx normal(-delta.imag(), delta.real());
125  cplx map_bottom_left;
126  cplx map_top_right;
127  if (std::abs(delta) < 3.0)
128  { // set minimum bound on distance (we do not want to have numerical instabilities) and 3.0 performs fine...
129  map_bottom_left = start + cplx(0, -3);
130  map_top_right = start + cplx(3, 3);
131  }
132  else
133  {
134  map_bottom_left = start - normal;
135  map_top_right = start + delta + normal;
136  }
137 
138  hsignature_ = 0; // reset local signature
139 
140  std::vector<double> imag_proposals(5);
141 
142  // iterate path
143  while(path_start != path_end)
144  {
145  cplx z1 = fun_cplx_point(*path_start);
146  cplx z2 = fun_cplx_point(*std::next(path_start));
147 
148  for (std::size_t l=0; l<obstacles->size(); ++l) // iterate all obstacles
149  {
150  cplx obst_l = obstacles->at(l)->getCentroidCplx();
151  //cplx f0 = (long double) prescaler * std::pow(obst_l-map_bottom_left,a) * std::pow(obst_l-map_top_right,b);
152  cplx f0 = (long double) cfg_->hcp.h_signature_prescaler * (long double)a*(obst_l-map_bottom_left) * (long double)b*(obst_l-map_top_right);
153 
154  // denum contains product with all obstacles exepct j==l
155  cplx Al = f0;
156  for (std::size_t j=0; j<obstacles->size(); ++j)
157  {
158  if (j==l)
159  continue;
160  cplx obst_j = obstacles->at(j)->getCentroidCplx();
161  cplx diff = obst_l - obst_j;
162  //if (diff.real()!=0 || diff.imag()!=0)
163  if (std::abs(diff)<0.05) // skip really close obstacles
164  continue;
165  else
166  Al /= diff;
167  }
168  // compute log value
169  double diff2 = std::abs(z2-obst_l);
170  double diff1 = std::abs(z1-obst_l);
171  if (diff2 == 0 || diff1 == 0)
172  continue;
173  double log_real = std::log(diff2)-std::log(diff1);
174  // complex ln has more than one solution -> choose minimum abs angle -> paper
175  double arg_diff = std::arg(z2-obst_l)-std::arg(z1-obst_l);
176  imag_proposals.at(0) = arg_diff;
177  imag_proposals.at(1) = arg_diff+2*M_PI;
178  imag_proposals.at(2) = arg_diff-2*M_PI;
179  imag_proposals.at(3) = arg_diff+4*M_PI;
180  imag_proposals.at(4) = arg_diff-4*M_PI;
181  double log_imag = *std::min_element(imag_proposals.begin(),imag_proposals.end(),smaller_than_abs);
182  cplx log_value(log_real,log_imag);
183  //cplx log_value = std::log(z2-obst_l)-std::log(z1-obst_l); // the principal solution doesn't seem to work
184  hsignature_ += Al*log_value;
185  }
186  ++path_start;
187  }
188  }
189 
190 
195  virtual bool isEqual(const EquivalenceClass& other) const
196  {
197  const HSignature* hother = dynamic_cast<const HSignature*>(&other); // TODO: better architecture without dynamic_cast
198  if (hother)
199  {
200  double diff_real = std::abs(hother->hsignature_.real() - hsignature_.real());
201  double diff_imag = std::abs(hother->hsignature_.imag() - hsignature_.imag());
202  if (diff_real<=cfg_->hcp.h_signature_threshold && diff_imag<=cfg_->hcp.h_signature_threshold)
203  return true; // Found! Homotopy class already exists, therefore nothing added
204  }
205  else
206  ROS_ERROR("Cannot compare HSignature equivalence classes with types other than HSignature.");
207 
208  return false;
209  }
210 
215  virtual bool isValid() const
216  {
217  return std::isfinite(hsignature_.real()) && std::isfinite(hsignature_.imag());
218  }
219 
224  virtual bool isReasonable() const
225  {
226  return true;
227  }
228 
233  const std::complex<long double>& value() const {return hsignature_;}
234 
235 
236 private:
237 
238  const TebConfig* cfg_;
239  std::complex<long double> hsignature_;
240 };
241 
242 
243 
244 
245 
254 class HSignature3d : public EquivalenceClass
255 {
256 public:
261  HSignature3d(const TebConfig& cfg) : cfg_(&cfg) {}
262 
263 
281  template<typename BidirIter, typename Fun>
282  void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer* obstacles,
283  boost::optional<TimeDiffSequence::iterator> timediff_start, boost::optional<TimeDiffSequence::iterator> timediff_end)
284  {
285  hsignature3d_.resize(obstacles->size());
286 
287  std::advance(path_end, -1); // reduce path_end by 1 (since we check line segments between those path points)
288 
289  constexpr int num_int_steps_per_segment = 10;
290 
291  for (std::size_t l = 0; l < obstacles->size(); ++l) // iterate all obstacles
292  {
293  double H = 0;
294  double transition_time = 0;
295  double next_transition_time = 0;
296  BidirIter path_iter;
297  TimeDiffSequence::iterator timediff_iter;
298 
299  Eigen::Vector3d s1 (obstacles->at(l)->getCentroid()(0), obstacles->at(l)->getCentroid()(1), 0);
300  double t = 120; // some large value for defining the end point of the obstacle/"conductor" model
301  Eigen::Vector3d s2;
302  obstacles->at(l)->predictCentroidConstantVelocity(t, s2.head(2));
303  s2[2] = t;
304  Eigen::Vector3d ds = s2 - s1;
305  double ds_sq_norm = ds.squaredNorm(); // by definition not zero as t > 0 (3rd component)
306 
307  // iterate path
308  for (path_iter = path_start, timediff_iter = timediff_start.get(); path_iter != path_end; ++path_iter, ++timediff_iter)
309  {
310  std::complex<long double> z1 = fun_cplx_point(*path_iter);
311  std::complex<long double> z2 = fun_cplx_point(*std::next(path_iter));
312 
313  transition_time = next_transition_time;
314  if (timediff_start == boost::none || timediff_end == boost::none) // if no time information is provided yet, approximate transition time
315  next_transition_time += std::abs(z2 - z1) / cfg_->robot.max_vel_x; // Approximate the time, if no time is known
316  else // otherwise use the time information from the teb trajectory
317  {
318  if (std::distance(path_iter, path_end) != std::distance(timediff_iter, timediff_end.get()))
319  ROS_ERROR("Size of poses and timediff vectors does not match. This is a bug.");
320  next_transition_time += (*timediff_iter)->dt();
321  }
322 
323  Eigen::Vector3d direction_vec;
324  direction_vec[0] = z2.real() - z1.real();
325  direction_vec[1] = z2.imag() - z1.imag();
326  direction_vec[2] = next_transition_time - transition_time;
327 
328  if(direction_vec.norm() < 1e-15) // Coincident poses
329  continue;
330 
331  Eigen::Vector3d r(z1.real(), z1.imag(), transition_time);
332  Eigen::Vector3d dl = 1.0/static_cast<double>(num_int_steps_per_segment) * direction_vec; // Integrate with multiple steps between each pose
333  Eigen::Vector3d p1, p2, d, phi;
334  for (int i = 0; i < num_int_steps_per_segment; ++i, r += dl)
335  {
336  p1 = s1 - r;
337  p2 = s2 - r;
338  d = (ds.cross(p1.cross(p2))) / ds_sq_norm;
339  phi = 1.0 / d.squaredNorm() * ((d.cross(p2) / p2.norm()) - (d.cross(p1) / p1.norm()));
340  H += phi.dot(dl);
341  }
342  }
343 
344  // normalize to 1
345  hsignature3d_.at(l) = H/(4.0*M_PI);
346  }
347  }
348 
359  virtual bool isEqual(const EquivalenceClass& other) const
360  {
361  const HSignature3d* hother = dynamic_cast<const HSignature3d*>(&other); // TODO: better architecture without dynamic_cast
362  if (hother)
363  {
364  if (hsignature3d_.size() == hother->hsignature3d_.size())
365  {
366  for(size_t i = 0; i < hsignature3d_.size(); ++i)
367  {
368  // If the H-Signature for one obstacle is below this threshold, that obstacle is far away from the planned trajectory,
369  // and therefore ignored in the homotopy class planning
370  if (std::abs(hother->hsignature3d_.at(i)) < cfg_->hcp.h_signature_threshold || std::abs(hsignature3d_.at(i)) < cfg_->hcp.h_signature_threshold)
371  continue;
372 
373  if (boost::math::sign(hother->hsignature3d_.at(i)) != boost::math::sign(hsignature3d_.at(i)))
374  return false; // Signatures are not equal, new homotopy class
375  }
376  return true; // Found! Homotopy class already exists, therefore nothing added
377  }
378  }
379  else
380  ROS_ERROR("Cannot compare HSignature3d equivalence classes with types other than HSignature3d.");
381 
382  return false;
383  }
384 
389  virtual bool isValid() const
390  {
391  for(const double& value : hsignature3d_)
392  {
393  if (!std::isfinite(value))
394  return false;
395  }
396  return true;
397  }
398 
403  virtual bool isReasonable() const
404  {
405  for(const double& value : hsignature3d_)
406  {
407  if (value > 1.0)
408  return false;
409  }
410  return true;
411  }
412 
417  const std::vector<double>& values() const {return hsignature3d_;}
418 
419 private:
420  const TebConfig* cfg_;
421  std::vector<double> hsignature3d_;
422 };
423 
424 
425 } // namespace teb_local_planner
426 
427 
428 #endif /* H_SIGNATURE_H_ */
teb_local_planner::HSignature3d::isValid
virtual bool isValid() const
Check if the equivalence value is detected correctly.
Definition: h_signature.h:425
teb_local_planner::HSignature::calculateHSignature
void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer *obstacles)
Calculate the H-Signature of a path.
Definition: h_signature.h:169
teb_local_planner::HSignature3d::HSignature3d
HSignature3d(const TebConfig &cfg)
Constructor accepting a TebConfig.
Definition: h_signature.h:297
teb_local_planner::HSignature3d::hsignature3d_
std::vector< double > hsignature3d_
Definition: h_signature.h:457
teb_local_planner::HSignature::cfg_
const TebConfig * cfg_
Definition: h_signature.h:310
teb_local_planner::HSignature3d::isEqual
virtual bool isEqual(const EquivalenceClass &other) const
Check if two candidate classes are equivalent.
Definition: h_signature.h:395
teb_local_planner::HSignature::HSignature
HSignature(const TebConfig &cfg)
Constructor accepting a TebConfig.
Definition: h_signature.h:148
equivalence_relations.h
ros.h
teb_local_planner::HSignature3d::isReasonable
virtual bool isReasonable() const
Check if the trajectory is non-looping around any obstacle. Values greater than 1 indicate a looping ...
Definition: h_signature.h:439
teb_local_planner::TebConfig::HomotopyClasses::h_signature_threshold
double h_signature_threshold
Two h-signatures are assumed to be equal, if both the difference of real parts and complex parts are ...
Definition: teb_config.h:202
teb_local_planner::HSignature3d::calculateHSignature
void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer *obstacles, boost::optional< TimeDiffSequence::iterator > timediff_start, boost::optional< TimeDiffSequence::iterator > timediff_end)
Calculate the H-Signature of a path.
Definition: h_signature.h:318
teb_local_planner::TebConfig::hcp
struct teb_local_planner::TebConfig::HomotopyClasses hcp
teb_local_planner::HSignature3d::values
const std::vector< double > & values() const
Get the current h-signature (read-only)
Definition: h_signature.h:453
teb_local_planner::TebConfig::HomotopyClasses::h_signature_prescaler
double h_signature_prescaler
Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly ...
Definition: teb_config.h:201
teb_local_planner::HSignature::isReasonable
virtual bool isReasonable() const
Check if the trajectory is non-looping around an obstacle.
Definition: h_signature.h:296
teb_local_planner::EquivalenceClass::EquivalenceClass
EquivalenceClass()
Default constructor.
Definition: equivalence_relations.h:106
teb_local_planner::HSignature::isEqual
virtual bool isEqual(const EquivalenceClass &other) const
Check if two candidate classes are equivalent.
Definition: h_signature.h:267
misc.h
obstacles.h
teb_config.h
timed_elastic_band.h
teb_local_planner::ObstContainer
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:333
teb_local_planner::TebConfig::robot
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
d
d
teb_local_planner::HSignature::isValid
virtual bool isValid() const
Check if the equivalence value is detected correctly.
Definition: h_signature.h:287
start
ROSCPP_DECL void start()
teb_local_planner::TebConfig::Robot::max_vel_x
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:99
teb_local_planner::HSignature::value
const std::complex< long double > & value() const
Get the current value of the h-signature (read-only)
Definition: h_signature.h:305
ROS_ERROR
#define ROS_ERROR(...)
teb_local_planner::HSignature::hsignature_
std::complex< long double > hsignature_
Definition: h_signature.h:311
teb_local_planner::HSignature3d::cfg_
const TebConfig * cfg_
Definition: h_signature.h:456
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::smaller_than_abs
bool smaller_than_abs(double i, double j)
Small helper function: check if |a|<|b|.
Definition: misc.h:123
t
geometry_msgs::TransformStamped t


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