ManagedObstacle.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package armar6_skills::ArmarXObjects::DynamicObstacleManager
17  * @author Fabian PK ( fabian dot peller-konrad at kit dot edu )
18  * @date 2020
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #include "ManagedObstacle.h"
24 
25 // STD/STL
26 #include <string>
27 #include <vector>
28 
29 // Ice
30 #include <Ice/Current.h>
31 using namespace Ice;
32 
33 // OpenCV
34 #include <opencv2/core.hpp>
35 
36 // Eigen
37 #include <Eigen/Core>
38 
39 // ArmarX
40 #include <RobotAPI/interface/core/PoseBase.h>
42 
44 
45 #include <opencv2/core/core_c.h>
46 
47 using namespace Eigen;
48 using namespace armarx;
49 
50 namespace armarx
51 {
52 
53  double ManagedObstacle::calculateObstacleArea(const obstacledetection::Obstacle& o)
54  {
55  return M_PI * std::abs(o.axisLengthX) * std::abs(o.axisLengthY);
56  }
57 
58  bool ManagedObstacle::point_ellipsis_coverage(const Eigen::Vector2f e_origin, const float e_rx, const float e_ry, const float e_yaw, const Eigen::Vector2f point)
59  {
60  // See https://stackoverflow.com/questions/7946187/point-and-ellipse-rotated-position-test-algorithm
61  const float sin = std::sin(e_yaw);
62  const float cos = std::cos(e_yaw);
63 
64  const float a = cos * (point(0) - e_origin(0)) + sin * (point(1) - e_origin(1));
65  const float b = sin * (point(0) - e_origin(0)) - cos * (point(1) - e_origin(1));
66 
67  const float e_rx_sq = e_rx * e_rx;
68  const float e_ry_sq = e_ry * e_ry;
69 
70  return a * a * e_ry_sq + b * b * e_rx_sq <= e_rx_sq * e_ry_sq;
71  }
72 
73  float ManagedObstacle::ellipsis_ellipsis_coverage(const Eigen::Vector2f e1_origin, const float e1_rx, const float e1_ry, const float e1_yaw, const Eigen::Vector2f e2_origin, const float e2_rx, const float e2_ry, const float e2_yaw)
74  {
75  // We use a very simple approach here: We sample points in one ellipsis and check whether it lies in the other (https://www.quora.com/Is-it-possible-to-generate-random-points-within-a-given-rotated-ellipse-without-using-rejection-sampling)
76  // For a real approach to intersect two ellipsis see https://arxiv.org/pdf/1106.3787.pdf
77 
78  unsigned int SAMPLES = 100;
79  unsigned int matches = 0;
80  for (unsigned int i = 0; i < SAMPLES; ++i)
81  {
82  float theta = static_cast<float>(rand()) / static_cast<float>(RAND_MAX / 2 * M_PI);
83  float k = sqrt(static_cast<float>(rand()) / static_cast<float>(RAND_MAX));
84  Eigen::Vector2f sample(k * e2_rx * cos(theta), k * e2_ry * sin(theta));
85  //sample *= Eigen::Rotation2D(e2_yaw);
86  sample += e1_origin;
87 
88  if (ManagedObstacle::point_ellipsis_coverage(e1_origin, e1_rx, e1_ry, e1_yaw, sample))
89  {
90  matches++;
91  }
92  }
93 
94  return (1.0f * matches) / SAMPLES;
95  }
96 
97  float ManagedObstacle::line_segment_ellipsis_coverage(const Eigen::Vector2f e_origin, const float e_rx, const float e_ry, const float e_yaw, const Eigen::Vector2f line_seg_start, const Eigen::Vector2f line_seg_end)
98  {
99  // Again we discretize the line into n points and we check the coverage of those points
100  const Eigen::Vector2f difference_vec = line_seg_end - line_seg_start;
101  const Eigen::Vector2f difference_vec_normed = difference_vec.normalized();
102  const float distance = difference_vec.norm();
103  const unsigned int SAMPLES = std::max(distance / 10.0, 40.0);
104 
105  const Vector2f difference_start_origin = e_origin - line_seg_start;
106  const Vector2f difference_end_origin = e_origin - line_seg_end;
107 
108  if (difference_start_origin.norm() > std::max(e_rx, e_ry) && distance < std::max(e_rx, e_ry))
109  {
110  return 0.0;
111  }
112 
113  if (difference_end_origin.norm() > std::max(e_rx, e_ry) && distance < std::max(e_rx, e_ry))
114  {
115  return 0.0;
116  }
117 
118 
119  const float step_size = distance / SAMPLES;
120  const Eigen::Vector2f dir = difference_vec_normed * step_size;
121 
122  unsigned int samples_in_ellipsis = 0;
123 
124  // Sample over line segment with a fixed size
125  for (unsigned int i = 0; i < SAMPLES * 0.5; ++i)
126  {
127  Eigen::Vector2f start_sample = line_seg_start + i * dir;
128  Eigen::Vector2f end_sample = line_seg_end - i * dir;
129  unsigned int samples_in_ellipsis_this_iteration = 0;
130 
131  for (const auto& point :
132  {
133  start_sample, end_sample
134  })
135  {
136  if (ManagedObstacle::point_ellipsis_coverage(e_origin, e_rx, e_ry, e_yaw, point))
137  {
138  ++samples_in_ellipsis;
139  ++samples_in_ellipsis_this_iteration;
140  }
141  }
142 
143  if (samples_in_ellipsis_this_iteration == 2)
144  {
145  // Last two points (from the outside) were inside this ellipsis, so the
146  // remaining ones are as well simce ellipsis are concave. Consider this line
147  // segment as explained by the obstacle and bail early.
148  const unsigned int remaining_samples = SAMPLES - 2 * (i + 1);
149  return (1.0f * samples_in_ellipsis + remaining_samples) / SAMPLES;
150  }
151  }
152  return (1.0f * samples_in_ellipsis) / SAMPLES; // only if one point or no point in ellipsis
153  }
154 
155  void ManagedObstacle::update_position(const unsigned int thickness)
156  {
157  if (line_matches.size() < 2)
158  {
159  return;
160  }
161 
162  ARMARX_DEBUG << "Obstacle " << m_obstacle.name << " has " << line_matches.size() << " matching line segments since last update";
163 
164  std::vector<float> x_pos;
165  std::vector<float> y_pos;
166  for (Eigen::Vector2f& match : line_matches)
167  {
168  ARMARX_DEBUG << "Match: " << match;
169  x_pos.push_back(match(0));
170  y_pos.push_back(match(1));
171  }
172 
173  cv::Mat x(x_pos.size(), 1, CV_32F, x_pos.data());
174  cv::Mat y(y_pos.size(), 1, CV_32F, y_pos.data());
175 
176  ARMARX_DEBUG << "X: " << x;
177  ARMARX_DEBUG << "Y: " << y;
178 
179  cv::Mat data(x_pos.size(), 2, CV_32F);
180  x.col(0).copyTo(data.col(0));
181  y.col(0).copyTo(data.col(1));
182 
183  ARMARX_DEBUG << "Data: " << data;
184 
185  cv::PCA pca(data, cv::Mat(), CV_PCA_DATA_AS_ROW, 2);
186 
187  cv::Mat mean = pca.mean;
188  ARMARX_DEBUG << "Mean: " << mean;
189  cv::Mat eigenvalues = pca.eigenvalues;
190  ARMARX_DEBUG << "Eigenvalues: " << eigenvalues;
191  cv::Mat eigenvectors = pca.eigenvectors;
192  ARMARX_DEBUG << "Eigenvectors: " << eigenvectors;
193 
194  Eigen::Vector2f pca_center(mean.at<float>(0, 0), mean.at<float>(0, 1));
195  Eigen::Vector2f pca1_direction(eigenvectors.at<float>(0, 0), eigenvectors.at<float>(0, 1));
196  Eigen::Vector2f pca2_direction(eigenvectors.at<float>(1, 0), eigenvectors.at<float>(1, 1));
197  double pca1_eigenvalue = eigenvalues.at<float>(0, 0);
198  double pca2_eigenvalue = eigenvalues.at<float>(1, 0);
199 
200  ARMARX_DEBUG << "PCA: Mean: " << pca_center;
201  ARMARX_DEBUG << "PCA1: Eigenvector: " << pca1_direction << ", Eigenvalue: " << pca1_eigenvalue;
202  ARMARX_DEBUG << "PCA2: Eigenvector: " << pca2_direction << ", Eigenvalue: " << pca2_eigenvalue;
203 
204  // calculate yaw of best line (should be close to current yaw)
205  const Eigen::Vector2f difference_vec = pca1_direction;
206  const Eigen::Vector2f center_vec = pca_center;
207  //const Eigen::Vector2f difference_vec1_normed = difference_vec.normalized();
208 
209  const float yaw1 = getXAxisAngle(difference_vec);
210  const float yaw2 = getXAxisAngle(-1 * difference_vec);
211 
212  const float diff_origin_yaw1 = std::abs(yaw1 - m_obstacle.yaw);
213  const float diff_origin_yaw2 = std::abs(yaw2 - m_obstacle.yaw);
214  const float diff_origin_yaw1_opposite = std::abs(2 * M_PI - diff_origin_yaw1);
215  const float diff_origin_yaw2_opposite = std::abs(2 * M_PI - diff_origin_yaw2);
216 
217 
218  float yaw = yaw2;
219  if ((diff_origin_yaw1 < diff_origin_yaw2 && diff_origin_yaw1 < diff_origin_yaw2_opposite) || (diff_origin_yaw1_opposite < diff_origin_yaw2 && diff_origin_yaw1_opposite < diff_origin_yaw2_opposite))
220  {
221  yaw = yaw1;
222  }
223 
224  // Print matches to debug drawer
225  //const std::string debug_line_name = "line_segment_input_" + std::to_string(m_input_index++);
226  //const armarx::Vector3BasePtr start_vec_3d{new Vector3(best_start(0), best_start(1), 50)};
227  //const armarx::Vector3BasePtr end_vec_3d{new Vector3(best_end(0), best_end(1), 50)};
228  //const armarx::Vector3BasePtr center_vec_3d{new Vector3(center_vec(0), center_vec(1), 50)};
229  //const armarx::Vector3BasePtr difference_vec_normed_3d{new Vector3(difference_vec1_normed(0), difference_vec1_normed(1), 0)};
230  //debug_drawer->setCylinderVisu(layer_name, debug_line_name, center_vec_3d, difference_vec_normed_3d, max_length, 15.f, armarx::DrawColor{1, 0, 0, 0.8});
231  //debug_drawer->setSphereVisu(layer_name, debug_line_name + "_ref", start_vec_3d, armarx::DrawColor{1, 1, 0, 0.8}, 35);
232  //debug_drawer->setSphereVisu(layer_name, debug_line_name + "_ref2", end_vec_3d, armarx::DrawColor{0, 1, 0, 0.8}, 35);
233 
234  // Udate position buffer with new best line
235  position_buffer.at(position_buffer_index++) = std::make_tuple(center_vec(0), center_vec(1), yaw, sqrt(pca1_eigenvalue) * 1.3, std::max(1.0f * thickness, static_cast<float>(sqrt(pca2_eigenvalue)) * 1.3f)); // add 30% security margin to length of pca
236  position_buffer_index %= position_buffer.size();
237 
238  position_buffer_fillctr++;
239  position_buffer_fillctr = std::min(position_buffer_fillctr, static_cast<unsigned int>(position_buffer.size()));
240 
241  // Calculate means from position buffer
242  double sum_x_pos = 0;
243  double sum_y_pos = 0;
244  double sum_yaw = 0;
245  double sum_sin_yaw = 0;
246  double sum_cos_yaw = 0;
247  double sum_axisX = 0;
248  double sum_axisY = 0;
249 
250  std::string yaws;
251  for (unsigned int i = 0; i < position_buffer_fillctr; ++i)
252  {
253  double current_x_pos = std::get<0>(position_buffer[i]);
254  double current_y_pos = std::get<1>(position_buffer[i]);
255  double current_yaw = std::get<2>(position_buffer[i]);
256  double current_axisX = std::get<3>(position_buffer[i]);
257  double current_axisY = std::get<4>(position_buffer[i]);
258  sum_x_pos += current_x_pos;
259  sum_y_pos += current_y_pos;
260  sum_yaw += current_yaw;
261  sum_sin_yaw += sin(current_yaw);
262  sum_cos_yaw += cos(current_yaw);
263  sum_axisX += current_axisX;
264  sum_axisY += current_axisY;
265 
266  yaws += std::to_string(current_yaw) + ", ";
267  }
268 
269  double mean_x_pos = sum_x_pos / position_buffer_fillctr;
270  double mean_y_pos = sum_y_pos / position_buffer_fillctr;
271  double mean_yaw = atan2((1.0 / position_buffer_fillctr) * sum_sin_yaw, (1.0 / position_buffer_fillctr) * sum_cos_yaw); //sum_yaw / position_buffer_fillctr; //std::fmod(sum_yaw, 2.0 * M_PI);
272  double mean_axisX = sum_axisX / position_buffer_fillctr;
273  double mean_axisY = sum_axisY / position_buffer_fillctr;
274  mean_yaw = normalizeYaw(mean_yaw);
275 
276  // Update position and size of obstacle
277  m_obstacle.posX = mean_x_pos;
278  m_obstacle.posY = mean_y_pos;
279  m_obstacle.refPosX = mean_x_pos;
280  m_obstacle.refPosY = mean_y_pos;
281  m_obstacle.yaw = mean_yaw;
282  //if (mean_axisX > m_obstacle.axisLengthX)
283  //{
284  m_obstacle.axisLengthX = mean_axisX;
285  //}
286  //if (mean_axisY > m_obstacle.axisLengthY)
287  //{
288  m_obstacle.axisLengthY = mean_axisY;
289  //}
290 
291  line_matches.clear();
292  m_updated = true;
293  }
294 
295  float ManagedObstacle::normalizeYaw(float yaw) const
296  {
297  float pi2 = 2.0 * M_PI;
298  while (yaw < 0)
299  {
300  yaw += pi2;
301  }
302  while (yaw > pi2)
303  {
304  yaw -= pi2;
305  }
306  return yaw;
307  }
308 
309  float ManagedObstacle::getAngleBetweenVectors(const Eigen::Vector2f& v1, const Eigen::Vector2f& v2) const
310  {
311  // Returns an angle between 0 and 180 degree (the minimum angle between the two vectors)
312  const Eigen::Vector2f v1_vec_normed = v1.normalized();
313  const Eigen::Vector2f v2_vec_normed = v2.normalized();
314  const float dot_product_vec = v1_vec_normed(0) * v2_vec_normed(0) + v1_vec_normed(1) * v2_vec_normed(1);
315  float yaw = acos(dot_product_vec);
316  return yaw;
317  }
318 
319  float ManagedObstacle::getXAxisAngle(const Eigen::Vector2f& v) const
320  {
321  // Returns an angle between 0 and 360 degree (counterclockwise from x axis)
322  const Eigen::Vector2f v_vec_normed = v.normalized();
323  const float dot_product_vec = v_vec_normed(0);
324  const float cross_product_vec = v_vec_normed(1);
325  float yaw = acos(dot_product_vec);
326  if (cross_product_vec < 0)
327  {
328  yaw = 2 * M_PI - yaw;
329  }
330  return yaw;
331  }
332 }
GfxTL::sqrt
VectorXD< D, T > sqrt(const VectorXD< D, T > &a)
Definition: VectorXD.h:662
Eigen
Definition: Elements.h:36
armarx::navigation::algorithm::getAngleBetweenVectors
float getAngleBetweenVectors(const Eigen::Vector2f &v1, const Eigen::Vector2f &v2)
Definition: CircularPathSmoothing.cpp:26
Pose.h
ManagedObstacle.h
armarx::ctrlutil::a
double a(double t, double a0, double j)
Definition: CtrlUtil.h:45
armarx::abs
std::vector< T > abs(const std::vector< T > &v)
Definition: VectorHelpers.h:253
armarx::mean
std::optional< float > mean(const boost::circular_buffer< NameValueMap > &buffer, const std::string &key)
Definition: KinematicUnitGuiPlugin.cpp:1615
M_PI
#define M_PI
Definition: MathTools.h:17
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
max
T max(T t1, T t2)
Definition: gdiam.h:48
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:40
Ice
Definition: DBTypes.cpp:64
armarx::ctrlutil::v
double v(double t, double v0, double a0, double j)
Definition: CtrlUtil.h:39
armarx::skills::gui::matches
bool matches(std::string skillName, std::vector< std::string > &searches)
Definition: SkillManagerWrapper.cpp:59
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:88
Logging.h
min
T min(T t1, T t2)
Definition: gdiam.h:42
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28