LaserScannerObstacleDetection.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 Armar6Skills::ArmarXObjects::LaserObstacleDetection
17 * @author Christian R. G. Dreher <c.dreher@kit.edu>
18 * @date 2020
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
23
25
26// ArmarX
28
29#include <RobotAPI/interface/core/PoseBase.h>
31
32using namespace armarx;
33
34
35const std::string LaserScannerObstacleDetection::default_name = "LaserScannerObstacleDetection";
36
38 m_enabled(true),
39 m_only_submit_first_n_results(-1),
40 m_max_distance_to_put_together(100),
41 m_max_yaw_difference(M_PI / 4),
42 m_periodic_task_interval(500),
43 m_accept_lines_after(100)
44{
45}
46
47void
49{
50 m_last_accepted_lines = IceUtil::Time::now();
51}
52
53void
55{
57 this, &LaserScannerObstacleDetection::eval_obstacles, m_periodic_task_interval);
58 m_eval_obstacles->start();
59}
60
61void
63{
64 m_eval_obstacles->stop();
65}
66
67void
71
72float
73LaserScannerObstacleDetection::get_distance_from_point_to_line_segment(
74 const Eigen::Vector2f& start,
75 const Eigen::Vector2f& end,
76 const Eigen::Vector2f& p) const
77{
78 // Return minimum distance between line segment l (start = v, end = w) and point p
79 const Eigen::Vector2f& v = start;
80 const Eigen::Vector2f& w = end;
81 const Eigen::Vector2f vp = p - v;
82 const Eigen::Vector2f vw = w - v;
83 const float line_length_sq = vw(0) * vw(0) + vw(1) * vw(1);
84
85
86 if (line_length_sq == 0.0)
87 {
88 ARMARX_ERROR << "Got invalid line segment!";
89 return 0;
90 }
91
92 // Consider the line extending the segment, parameterized as v + t (w - v).
93 // We find projection of point p onto the line.
94 // It falls where t = [(p-v) . (w-v)] / |w-v|^2
95 // We clamp t from [0,1] to handle points outside the segment vw.
96
97 const float pv_dot_wv = vp(0) * vw(0) + vp(1) * vw(1);
98 const float t = std::max(0.0f, std::min(1.0f, pv_dot_wv / line_length_sq));
99 const Eigen::Vector2f projection = v + (t * vw);
100 const float distance = (projection - p).norm();
101 return distance;
102}
103
104float
105LaserScannerObstacleDetection::get_angle_between_vectors(const Eigen::Vector2f& v1,
106 const Eigen::Vector2f& v2) const
107{
108 // Returns an angle between 0 and 180 degree (the minimum angle between the two vectors)
109 const Eigen::Vector2f v1_vec_normed = v1.normalized();
110 const Eigen::Vector2f v2_vec_normed = v2.normalized();
111 const float dot_product_vec =
112 v1_vec_normed(0) * v2_vec_normed(0) + v1_vec_normed(1) * v2_vec_normed(1);
113 float yaw = acos(dot_product_vec);
114 if (yaw >= M_PI)
115 {
116 yaw -= M_PI;
117 }
118 return yaw;
119}
120
121void
122LaserScannerObstacleDetection::eval_obstacles()
123{
124 laser_scanner_feature_extraction::LineSegment2DChainSeq lines;
125
126 {
127 std::unique_lock l{m_lines_buffer_mutex};
128 lines = m_lines_buffer;
129 m_lines_buffer.clear();
130 }
131
132 if (lines.empty() || m_only_submit_first_n_results == 0)
133 {
134 return;
135 }
136
137 bool update_found = false;
138 int lines_before = lines.size();
139 IceUtil::Time started = IceUtil::Time::now();
140 do
141 {
142 update_found = false;
143 if (lines.size() < 2)
144 {
145 break;
146 }
147
148 // search for lines to put together
149 unsigned int remove1 = 0;
150 unsigned int remove2 = 0;
151
152 // TODO(fabian..)
153 // for (unsigned int i = 0; i < lines.size() - 1; ++i)
154 // {
155 // remove1 = i;
156 // const LineSegment2D& line1 = lines[i];
157 // const Eigen::Vector2f origin_start(line1.start.e0, line1.start.e1);
158 // const Eigen::Vector2f origin_end(line1.end.e0, line1.end.e1);
159 // for (unsigned int j = i + 1; j < lines.size(); ++j)
160 // {
161 // remove2 = j;
162 // const LineSegment2D& line2 = lines[j];
163 // Eigen::Vector2f start(line2.start.e0, line2.start.e1);
164 // Eigen::Vector2f end(line2.end.e0, line2.end.e1);
165
166 // // check yaws
167 // float yaw = get_angle_between_vectors((origin_end - origin_start), (end - start));
168
169
170 // // check points and distances
171 // if (yaw < m_max_yaw_difference && (get_distance_from_point_to_line_segment(line1, start) < m_max_distance_to_put_together || get_distance_from_point_to_line_segment(line1, end) < m_max_distance_to_put_together))
172 // {
173 // // Group those lines. Only take longets one
174 // float length_os_s = (origin_start - start).norm();
175 // float length_os_e = (origin_start - end).norm();
176 // float length_oe_s = (origin_end - start).norm();
177 // float length_oe_e = (origin_end - end).norm();
178
179 // Eigen::Vector2f new_line_s;
180 // Eigen::Vector2f new_line_e;
181 // if (length_os_s > length_os_e && length_os_s > length_oe_s && length_os_s > length_oe_e)
182 // {
183 // // length_os_s is maximum
184 // new_line_s = origin_start;
185 // new_line_e = start;
186 // }
187 // else if (length_os_e > length_oe_s && length_os_e > length_oe_e)
188 // {
189 // // length_os_e is maximum
190 // new_line_s = origin_start;
191 // new_line_e = end;
192 // }
193 // else if (length_oe_s > length_oe_e)
194 // {
195 // // length_oe_s is maximum
196 // new_line_s = origin_end;
197 // new_line_e = start;
198 // }
199 // else
200 // {
201 // // length_oe_s is maximum
202 // new_line_s = origin_end;
203 // new_line_e = end;
204 // }
205
206 // LineSegment2D new_line;
207 // new_line.start.e0 = new_line_s(0);
208 // new_line.start.e1 = new_line_s(1);
209 // new_line.end.e0 = new_line_e(0);
210 // new_line.end.e1 = new_line_e(1);
211
212 // lines.push_back(new_line);
213 // update_found = true;
214 // break;
215 // }
216
217 // }
218 // if (update_found)
219 // {
220 // break;
221 // }
222 // }
223
224 // remove lines from update
225 if (update_found)
226 {
227 ARMARX_CHECK(remove2 > remove1);
228 lines.erase(lines.begin() + remove2);
229 lines.erase(lines.begin() + remove1);
230 }
231 } while (update_found);
232
233 ARMARX_DEBUG << "Finished updating the " << lines_before << " lines. Now we have "
234 << lines.size() << " lines. The operation took "
235 << (IceUtil::Time::now() - started).toMilliSeconds() << "ms";
236
237 // Try to explain line segments by the obstacles from the obstacle avoidance environment.
238 std::vector<dynamicobstaclemanager::LineSegment> converted_lines;
239 for (const auto& chain : lines)
240 {
241
242 if (chain.size() < 2)
243 {
244 continue;
245 }
246
247 for (auto it = chain.begin(); it != chain.end() - 1; it++)
248 {
249 converted_lines.emplace_back(dynamicobstaclemanager::LineSegment{*it, *(it + 1)});
250 }
251 }
252 m_obstacle_manager->add_decayable_line_segments(converted_lines);
253
254
255 // Debug
256 if (m_only_submit_first_n_results > 0)
257 {
258 m_only_submit_first_n_results--;
259 }
260 ARMARX_DEBUG << "Finished update";
261}
262
263//void
264//LaserScannerObstacleDetection::reportExtractedEdges(
265// const std::vector<LineSegment2D>& lines,
266// const Ice::Current&)
267//{
268// {
269// std::lock_guard l{m_enabled_mutex};
270// if (! m_enabled or lines.empty())
271// {
272// return;
273// }
274// }
275
276// if ((IceUtil::Time::now() - m_last_accepted_lines).toMilliSeconds() > m_accept_lines_after)
277// {
278// std::unique_lock l{m_lines_buffer_mutex};
279// ARMARX_DEBUG << "Got " << lines.size() << " new extracted edges to buffer.";
280// m_lines_buffer.insert(m_lines_buffer.end(), lines.begin(), lines.end());
281// m_last_accepted_lines = IceUtil::Time::now();
282// }
283
284//}
285
286void
288{
289 std::lock_guard l{m_enabled_mutex};
290 m_enabled = enable;
291}
292
293void
295{
296 std::lock_guard l{m_enabled_mutex};
297 m_enabled = true;
298}
299
300void
302{
303 std::lock_guard l{m_enabled_mutex};
304 m_enabled = false;
305}
306
307std::string
312
315{
317
318 defs->component(m_obstacle_manager,
319 "DynamicObstacleManager",
320 "ObstacleManager",
321 "The name of the obstacle manager proxy");
322 defs->topic<LaserScannerFeaturesListener>();
323
324 defs->optional(m_only_submit_first_n_results,
325 "SubmitOnlyFirstNResults",
326 "Only send the first laser scanner result. -1 for all.");
327 defs->optional(m_max_distance_to_put_together,
328 "MaxDistanceOfLinesToGroup",
329 "Max distance in mm of two lines to put them together");
330 defs->optional(m_max_yaw_difference,
331 "MaxAngleDifferenceOfLinesToGroup",
332 "Max angle difference in yaw of two lines to put them together");
333 defs->optional(
334 m_periodic_task_interval, "UpdateInterval", "The interval to check the obstacles");
335 defs->optional(
336 m_accept_lines_after, "AcceptLinesAfter", "Accept new Lines for buffer every x ms");
337 defs->optional(m_enabled, "ActivateOnStartup", "Activate the component on startup.");
338
339 return defs;
340}
341
342void
344 const laser_scanner_feature_extraction::LineSegment2DChainSeq& globalLineSegmentChains,
345 const Ice::Current&)
346{
347 {
348 std::lock_guard l{m_enabled_mutex};
349 if (!m_enabled or globalLineSegmentChains.empty())
350 {
351 return;
352 }
353 }
354
355 if ((IceUtil::Time::now() - m_last_accepted_lines).toMilliSeconds() > m_accept_lines_after)
356 {
357 std::unique_lock l{m_lines_buffer_mutex};
358
359
360 ARMARX_DEBUG << "Got " << globalLineSegmentChains.size()
361 << " new extracted edges to buffer.";
362
363 m_lines_buffer.insert(
364 m_lines_buffer.end(), globalLineSegmentChains.begin(), globalLineSegmentChains.end());
365 m_last_accepted_lines = IceUtil::Time::now();
366 }
367}
#define M_PI
Definition MathTools.h:17
Default component property definition container.
Definition Component.h:70
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition Component.cpp:90
void onInitComponent() override
Pure virtual hook for the subclass.
void onDisconnectComponent() override
Hook for subclass.
void reportExtractedLineSegments(const laser_scanner_feature_extraction::LineSegment2DChainSeq &globalLineSegmentChains, const Ice::Current &=Ice::Current()) override
void onConnectComponent() override
Pure virtual hook for the subclass.
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
void enable(const Ice::Current &=Ice::emptyCurrent) override
void setEnabled(bool enable, const Ice::Current &=Ice::emptyCurrent) override
void onExitComponent() override
Hook for subclass.
void disable(const Ice::Current &=Ice::emptyCurrent) override
std::string getDefaultName() const override
Retrieve default name of component.
The periodic task executes one thread method repeatedly using the time period specified in the constr...
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:196
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
This file offers overloads of toIce() and fromIce() functions for STL container types.
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
double norm(const Point &a)
Definition point.hpp:102
double distance(const Point &a, const Point &b)
Definition point.hpp:95