39 #ifndef H_SIGNATURE_H_
40 #define H_SIGNATURE_H_
67 class HSignature :
public EquivalenceClass
96 template<
typename B
idirIter,
typename Fun>
99 if (obstacles->empty())
110 int m = std::max( (
int)obstacles->size()-1, 5 );
112 int a = (int) std::ceil(
double(m)/2.0);
115 std::advance(path_end, -1);
117 typedef std::complex<long double> cplx;
121 cplx
start = fun_cplx_point(*path_start);
122 cplx end = fun_cplx_point(*path_end);
123 cplx delta = end-
start;
124 cplx normal(-delta.imag(), delta.real());
125 cplx map_bottom_left;
127 if (std::abs(delta) < 3.0)
129 map_bottom_left =
start + cplx(0, -3);
130 map_top_right =
start + cplx(3, 3);
134 map_bottom_left =
start - normal;
135 map_top_right =
start + delta + normal;
140 std::vector<double> imag_proposals(5);
143 while(path_start != path_end)
145 cplx z1 = fun_cplx_point(*path_start);
146 cplx z2 = fun_cplx_point(*std::next(path_start));
148 for (std::size_t l=0; l<obstacles->size(); ++l)
150 cplx obst_l = obstacles->at(l)->getCentroidCplx();
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);
156 for (std::size_t j=0; j<obstacles->size(); ++j)
160 cplx obst_j = obstacles->at(j)->getCentroidCplx();
161 cplx diff = obst_l - obst_j;
163 if (std::abs(diff)<0.05)
169 double diff2 = std::abs(z2-obst_l);
170 double diff1 = std::abs(z1-obst_l);
171 if (diff2 == 0 || diff1 == 0)
173 double log_real = std::log(diff2)-std::log(diff1);
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);
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)
206 ROS_ERROR(
"Cannot compare HSignature equivalence classes with types other than HSignature.");
238 const TebConfig*
cfg_;
254 class HSignature3d :
public EquivalenceClass
281 template<
typename B
idirIter,
typename Fun>
283 boost::optional<TimeDiffSequence::iterator> timediff_start, boost::optional<TimeDiffSequence::iterator> timediff_end)
287 std::advance(path_end, -1);
289 constexpr
int num_int_steps_per_segment = 10;
291 for (std::size_t l = 0; l < obstacles->size(); ++l)
294 double transition_time = 0;
295 double next_transition_time = 0;
297 TimeDiffSequence::iterator timediff_iter;
299 Eigen::Vector3d s1 (obstacles->at(l)->getCentroid()(0), obstacles->at(l)->getCentroid()(1), 0);
302 obstacles->at(l)->predictCentroidConstantVelocity(t, s2.head(2));
304 Eigen::Vector3d ds = s2 - s1;
305 double ds_sq_norm = ds.squaredNorm();
308 for (path_iter = path_start, timediff_iter = timediff_start.get(); path_iter != path_end; ++path_iter, ++timediff_iter)
310 std::complex<long double> z1 = fun_cplx_point(*path_iter);
311 std::complex<long double> z2 = fun_cplx_point(*std::next(path_iter));
313 transition_time = next_transition_time;
314 if (timediff_start == boost::none || timediff_end == boost::none)
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();
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;
328 if(direction_vec.norm() < 1e-15)
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;
333 Eigen::Vector3d p1, p2,
d, phi;
334 for (
int i = 0; i < num_int_steps_per_segment; ++i, r += dl)
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()));
373 if (boost::math::sign(hother->hsignature3d_.at(i)) != boost::math::sign(
hsignature3d_.at(i)))
380 ROS_ERROR(
"Cannot compare HSignature3d equivalence classes with types other than HSignature3d.");
393 if (!std::isfinite(value))
420 const TebConfig*
cfg_;