DynamicObstacleManager.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 "DynamicObstacleManager.h"
24 
25 #include <VirtualRobot/MathTools.h>
26 
27 // STD/STL
28 #include <string>
29 #include <vector>
30 #include <cmath>
31 #include <limits>
32 
33 // Ice
34 #include <Ice/Current.h>
35 using namespace Ice;
36 
37 // Eigen
38 #include <Eigen/Core>
39 using namespace Eigen;
40 
41 // Simox
42 #include <VirtualRobot/Nodes/RobotNode.h>
43 #include <VirtualRobot/XML/RobotIO.h>
44 
45 // ArmarX
46 #include <ArmarXCore/util/time.h>
48 #include <RobotAPI/interface/core/PoseBase.h>
50 
51 
52 using namespace armarx;
53 
54 
55 const std::string
56 armarx::DynamicObstacleManager::default_name = "DynamicObstacleManager";
57 
58 namespace armarx
59 {
60 
61  DynamicObstacleManager::DynamicObstacleManager() noexcept :
62  m_obstacle_index(0),
63  m_decay_after_ms(5000),
64  m_periodic_task_interval(500),
65  m_min_value_for_accepting(1000),
66  m_min_coverage_of_obstacles(0.7f),
67  m_min_coverage_of_line_samples_in_obstacle(0.9f),
68  m_min_size_of_obstacles(100),
69  m_min_length_of_lines(50),
70  m_max_size_of_obstacles(600),
71  m_max_length_of_lines(10000),
72  m_thickness_of_lines(200),
73  m_security_margin_for_obstacles(500),
74  m_security_margin_for_lines(400),
75  m_remove_enabled(false),
76  m_only_visualize(false),
77  m_allow_spwan_inside(false)
78  {
79 
80  }
81 
82 
83  std::string DynamicObstacleManager::getDefaultName() const
84  {
85  return DynamicObstacleManager::default_name;
86  }
87 
88 
89  void DynamicObstacleManager::onInitComponent()
90  {
91 
92  }
93 
94 
95  void DynamicObstacleManager::onConnectComponent()
96  {
97  m_decay_factor = m_periodic_task_interval;
98  m_access_bonus = m_periodic_task_interval;
99 
100  m_update_obstacles = new PeriodicTask<DynamicObstacleManager>(this,
101  &DynamicObstacleManager::update_decayable_obstacles, m_periodic_task_interval);
102  m_update_obstacles->start();
103  }
104 
105  void DynamicObstacleManager::onDisconnectComponent()
106  {
107  m_update_obstacles->stop();
108  }
109 
110  void DynamicObstacleManager::onExitComponent()
111  {
112 
113  }
114 
115  void DynamicObstacleManager::add_decayable_obstacle(const Eigen::Vector2f& e_origin, float e_rx, float e_ry, float e_yaw, const Ice::Current&)
116  {
117  // TODO
118  }
119 
120 
121  void DynamicObstacleManager::add_decayable_line_segment(const Eigen::Vector2f& line_start, const Eigen::Vector2f& line_end, const Ice::Current&)
122  {
123  TIMING_START(add_decayable_line_segment);
124  const Eigen::Vector2f difference_vec = line_end - line_start;
125  const float length = difference_vec.norm();
126  const Eigen::Vector2f center_vec = line_start + 0.5 * difference_vec;
127  const Eigen::Vector2f difference_vec_normed = difference_vec.normalized();
128  const float dot_product = difference_vec_normed(0);
129  const float cross_product = difference_vec_normed(1);
130  float yaw = acos(dot_product);
131 
132  if (cross_product < 0)
133  {
134  yaw = 2 * M_PI - yaw;
135  }
136 
137  if (length < m_min_length_of_lines)
138  {
139  return;
140  }
141 
142  {
143  std::shared_lock<std::shared_mutex> l(m_managed_obstacles_mutex);
144 
145  TIMING_START(add_decayable_line_segment_mutex);
146  // First check own obstacles
147  for (ManagedObstaclePtr& managed_obstacle : m_managed_obstacles)
148  {
149 
150  std::lock_guard<std::shared_mutex> l(managed_obstacle->m_mutex);
151  float coverage = ManagedObstacle::line_segment_ellipsis_coverage(
152  {managed_obstacle->m_obstacle.posX, managed_obstacle->m_obstacle.posY}, managed_obstacle->m_obstacle.axisLengthX, managed_obstacle->m_obstacle.axisLengthY, managed_obstacle->m_obstacle.yaw,
153  line_start, line_end);
154  //ARMARX_DEBUG << "The coverage of the new line to obstacle " << managed_obstacle.obstacle.name << "(" << ManagedObstacle::calculateObstacleArea(managed_obstacle.obstacle) << ") is " << coverage;
155  if (coverage >= m_min_coverage_of_line_samples_in_obstacle)
156  {
157  // Obstacle already in list. Increase counter and update current obstacle.
158  managed_obstacle->line_matches.push_back(line_start);
159  managed_obstacle->line_matches.push_back(line_end);
160  managed_obstacle->m_last_matched = IceUtil::Time::now();
161  TIMING_END(add_decayable_line_segment_mutex);
162  return;
163  }
164  }
165  TIMING_END(add_decayable_line_segment_mutex);
166  }
167 
168  // Second check the obstacles from the obstacle avoidance
169  /*for (const auto& published_obstacle : m_obstacle_detection->getObstacles())
170  {
171  float coverage = ManagedObstacle::line_segment_ellipsis_coverage(
172  {published_obstacle.posX, published_obstacle.posY}, published_obstacle.axisLengthX, published_obstacle.axisLengthY, published_obstacle.yaw,
173  line_start, line_end);
174  if (coverage >= m_min_coverage_of_line_samples_in_obstacle)
175  {
176  // If own managed obstacle we already updatet its value. If its a static obstacle from the obstacle avoidance, then we can't update the position anyway...
177  ARMARX_DEBUG << "Found the obstacle in the static obstacle list! Matching name: " << published_obstacle.name;
178  return;
179  }
180  }*/
181 
182  ARMARX_DEBUG << " No matching obstacle found. Create new obstacle and add to list";
183  ManagedObstaclePtr new_managed_obstacle(new ManagedObstacle());
184  new_managed_obstacle->m_obstacle.name = "managed_obstacle_" + std::to_string(m_obstacle_index++);
185  new_managed_obstacle->m_obstacle.posX = center_vec(0);
186  new_managed_obstacle->m_obstacle.posY = center_vec(1);
187  new_managed_obstacle->m_obstacle.refPosX = center_vec(0);
188  new_managed_obstacle->m_obstacle.refPosY = center_vec(1);
189  new_managed_obstacle->m_obstacle.yaw = yaw;
190  new_managed_obstacle->m_obstacle.axisLengthX = std::clamp(length * 0.5f, static_cast<float>(m_min_length_of_lines), static_cast<float>(m_max_length_of_lines));
191  new_managed_obstacle->m_obstacle.axisLengthY = m_thickness_of_lines;
192  new_managed_obstacle->m_obstacle.safetyMarginX = m_security_margin_for_lines;
193  new_managed_obstacle->m_obstacle.safetyMarginY = m_security_margin_for_lines;
194  new_managed_obstacle->m_last_matched = IceUtil::Time::now();
195  new_managed_obstacle->m_published = false;
196  new_managed_obstacle->m_value = m_min_value_for_accepting * 0.5;
197  new_managed_obstacle->position_buffer_index = 0;
198  new_managed_obstacle->position_buffer_fillctr = 0;
199  new_managed_obstacle->line_matches.push_back(line_start);
200  new_managed_obstacle->line_matches.push_back(line_end);
201 
202  {
203  std::lock_guard<std::shared_mutex> l(m_managed_obstacles_mutex);
204  m_managed_obstacles.push_back(new_managed_obstacle);
205  }
206  TIMING_END(add_decayable_line_segment);
207  }
208 
209  void DynamicObstacleManager::add_decayable_line_segments(const dynamicobstaclemanager::LineSegments& lines, const Ice::Current& c)
210  {
211  for (const auto& line : lines)
212  {
213  add_decayable_line_segment(line.lineStart, line.lineEnd, c);
214  }
215  }
216 
217 
218  void DynamicObstacleManager::remove_all_decayable_obstacles(const Ice::Current&)
219  {
220  std::lock_guard l(m_managed_obstacles_mutex);
221 
222  ARMARX_DEBUG << "Remove all obstacles from obstacle map by setting their value to -inf";
223  for (ManagedObstaclePtr& managed_obstacle : m_managed_obstacles)
224  {
225  managed_obstacle->m_value = std::numeric_limits<double>::min();
226  managed_obstacle->m_updated = true;
227  }
228  }
229 
230  void DynamicObstacleManager::remove_obstacle(const std::string& name, const Ice::Current&)
231  {
232  std::lock_guard l(m_managed_obstacles_mutex);
233 
234  ARMARX_DEBUG << "Remove Obstacle " << name << " from obstacle map and from obstacledetection";
235  for (ManagedObstaclePtr managed_obstacle : m_managed_obstacles)
236  {
237  if (managed_obstacle->m_obstacle.name == name)
238  {
239  managed_obstacle->m_value = std::numeric_limits<double>::min();
240  managed_obstacle->m_updated = true;
241  managed_obstacle->m_published = false;
242  break;
243  }
244  }
245  m_obstacle_detection->removeObstacle(name);
246  m_obstacle_detection->updateEnvironment();
247  }
248 
249  void DynamicObstacleManager::wait_unitl_obstacles_are_ready(const Ice::Current&)
250  {
251  ARMARX_INFO << "Waiting for obstacles to get ready";
252  usleep(2.0 * m_min_value_for_accepting);
253  ARMARX_INFO << "Finished waiting for obstacles";
254  }
255 
256 
257  float
258  DynamicObstacleManager::distanceToObstacle(const Eigen::Vector2f& agentPosition, float safetyRadius, const Eigen::Vector2f& goal, const Ice::Current&)
259  {
260  std::shared_lock<std::shared_mutex> l{m_managed_obstacles_mutex};
261 
262  const Eigen::Vector2f diff = goal - agentPosition;
263  const Eigen::Vector2f orthogonal_normalized = Eigen::Vector2f(Eigen::Rotation2Df(M_PI_2) * diff).normalized();
264 
265  const float sample_step = 5; // in [mm], sample step size towards goal.
266  const float distance_to_goal = diff.norm() + safetyRadius;
267 
268  float current_distance = safetyRadius;
269 
270  while (current_distance < distance_to_goal)
271  {
272  for (const auto& man_obstacle : m_managed_obstacles)
273  {
274  Eigen::Vector2f sample = agentPosition + ((goal - agentPosition).normalized() * current_distance);
275  Eigen::Vector2f sample_left = sample + (orthogonal_normalized * 250);
276  Eigen::Vector2f sample_right = sample - (orthogonal_normalized * 250);
277 
278  obstacledetection::Obstacle obstacle = man_obstacle->m_obstacle;
279  Eigen::Vector2f obstacle_origin{obstacle.posX, obstacle.posY};
280 
281  if (ManagedObstacle::point_ellipsis_coverage(obstacle_origin, obstacle.axisLengthX, obstacle.axisLengthY, obstacle.yaw, sample))
282  {
283  return current_distance - safetyRadius;
284  }
285 
286  if (ManagedObstacle::point_ellipsis_coverage(obstacle_origin, obstacle.axisLengthX, obstacle.axisLengthY, obstacle.yaw, sample_left))
287  {
288  return current_distance - safetyRadius;
289  }
290 
291  if (ManagedObstacle::point_ellipsis_coverage(obstacle_origin, obstacle.axisLengthX, obstacle.axisLengthY, obstacle.yaw, sample_right))
292  {
293  return current_distance - safetyRadius;
294  }
295  }
296 
297  current_distance += sample_step;
298  }
299 
300  return std::numeric_limits<float>::infinity();
301  }
302 
303 
304  void DynamicObstacleManager::directly_update_obstacle(const std::string& name, const Eigen::Vector2f& obs_pos, float e_rx, float e_ry, float e_yaw, const Ice::Current&)
305  {
306  obstacledetection::Obstacle new_unmanaged_obstacle;
307  new_unmanaged_obstacle.name = name;
308  new_unmanaged_obstacle.posX = obs_pos(0);
309  new_unmanaged_obstacle.posY = obs_pos(1);
310  new_unmanaged_obstacle.refPosX = obs_pos(0);
311  new_unmanaged_obstacle.refPosY = obs_pos(1);
312  new_unmanaged_obstacle.yaw = e_yaw;
313  new_unmanaged_obstacle.axisLengthX = std::clamp(e_rx, static_cast<float>(m_min_size_of_obstacles), static_cast<float>(m_max_size_of_obstacles));
314  new_unmanaged_obstacle.axisLengthY = std::clamp(e_ry, static_cast<float>(m_min_size_of_obstacles), static_cast<float>(m_max_size_of_obstacles));
315  new_unmanaged_obstacle.safetyMarginX = m_security_margin_for_obstacles;
316  new_unmanaged_obstacle.safetyMarginY = m_security_margin_for_obstacles;
317  m_obstacle_detection->updateObstacle(new_unmanaged_obstacle);
318  m_obstacle_detection->updateEnvironment();
319  }
320 
321 
322  void DynamicObstacleManager::update_decayable_obstacles()
323  {
324  ARMARX_DEBUG << "update obstacles";
325  IceUtil::Time started = IceUtil::Time::now();
326  std::vector<std::string> remove_obstacles;
327 
328  // Some debug definitions
329  viz::Layer obstacleLayer = arviz.layer(m_obstacle_manager_layer_name);
330 
331  // Update positions
332  {
333  ARMARX_DEBUG << "update obstacle position";
334  std::shared_lock<std::shared_mutex> l(m_managed_obstacles_mutex);
335  if (!m_managed_obstacles.size())
336  {
337  return;
338  }
339 
340  for (ManagedObstaclePtr& managed_obstacle : m_managed_obstacles)
341  {
342  std::lock_guard<std::shared_mutex> l(managed_obstacle->m_mutex);
343  managed_obstacle->update_position(m_thickness_of_lines);
344  }
345  }
346 
347  // Update obstacle avoidance
348  int checked_obstacles = 0;
349  bool updated = false;
350  int published_obstacles = 0;
351  int updated_obstacles = 0;
352  {
353  ARMARX_DEBUG << "update obstacle values and publish";
354  std::lock_guard l(m_managed_obstacles_mutex);
355  std::sort(m_managed_obstacles.begin(), m_managed_obstacles.end(), ManagedObstacle::ComparatorDESCPrt);
356 
357  checked_obstacles = m_managed_obstacles.size();
358 
359  for (ManagedObstaclePtr& managed_obstacle : m_managed_obstacles)
360  {
361  std::lock_guard<std::shared_mutex> l(managed_obstacle->m_mutex);
362  if (!managed_obstacle->m_updated)
363  {
364  managed_obstacle->m_value = std::max(-1.0f, managed_obstacle->m_value - m_decay_factor);
365  }
366  else
367  {
368  managed_obstacle->m_value = std::min(1.0f * m_decay_after_ms, managed_obstacle->m_value + m_access_bonus);
369  }
370 
371  if (managed_obstacle->m_published)
372  {
373  if (managed_obstacle->m_value < m_min_value_for_accepting)
374  {
375  updated_obstacles++;
376  managed_obstacle->m_published = false;
377  if (!m_only_visualize)
378  {
379  m_obstacle_detection->removeObstacle(managed_obstacle->m_obstacle.name);
380  updated = true;
381  }
382  }
383  else
384  {
385  published_obstacles++;
386  if (managed_obstacle->m_updated)
387  {
388  updated_obstacles++;
389  if (!m_only_visualize)
390  {
391  m_obstacle_detection->updateObstacle(managed_obstacle->m_obstacle);
392  updated = true;
393  }
394  //visualize_obstacle(obstacleLayer, managed_obstacle, armarx::DrawColor{0, 1, 1, std::min(0.9f, managed_obstacle->m_value / m_decay_after_ms)}, 50, false);
395  }
396  else
397  {
398  //visualize_obstacle(obstacleLayer, managed_obstacle, armarx::DrawColor{0, 1, 0, std::min(0.9f, managed_obstacle->m_value / m_decay_after_ms)}, 50, false);
399  }
400  }
401  }
402  else // if (!managed_obstacle.published)
403  {
404  if (managed_obstacle->m_value >= m_min_value_for_accepting)
405  {
406  published_obstacles++;
407  updated_obstacles++;
408  managed_obstacle->m_published = true;
409  if (!m_only_visualize)
410  {
411  m_obstacle_detection->updateObstacle(managed_obstacle->m_obstacle);
412  updated = true;
413  }
414  //visualize_obstacle(obstacleLayer, managed_obstacle, armarx::DrawColor{0, 1, 0, std::min(0.9f, managed_obstacle->m_value / m_decay_after_ms)}, 50, false);
415  }
416  else if (managed_obstacle->m_value < 0 && m_remove_enabled) // Completely forget the obstacle
417  {
418  remove_obstacles.push_back(managed_obstacle->m_obstacle.name);
419  }
420  else if (managed_obstacle->m_updated)
421  {
422  visualize_obstacle(obstacleLayer, managed_obstacle, armarx::DrawColor{1, 1, 1, std::min(0.9f, managed_obstacle->m_value / m_min_value_for_accepting)}, 40, true);
423  }
424  else
425  {
426  visualize_obstacle(obstacleLayer, managed_obstacle, armarx::DrawColor{1, 1, 1, std::min(0.9f, managed_obstacle->m_value / m_min_value_for_accepting)}, 40, true);
427  }
428  }
429  managed_obstacle->m_updated = false;
430  }
431  }
432 
433  if (updated)
434  {
435  ARMARX_DEBUG << "update environment";
436  m_obstacle_detection->updateEnvironment();
437  }
438  arviz.commit({obstacleLayer});
439 
440  if (!remove_obstacles.empty())
441  {
442  std::lock_guard<std::shared_mutex> l(m_managed_obstacles_mutex);
443  for (const auto& name : remove_obstacles)
444  {
445  // TODO schöner machen ohne loop. Iteratoren in main loop
446  m_managed_obstacles.erase(
447  std::remove_if(
448  m_managed_obstacles.begin(),
449  m_managed_obstacles.end(),
450  [&](const ManagedObstaclePtr & oc)
451  {
452  return oc->m_obstacle.name == name;
453  }
454  ),
455  m_managed_obstacles.end()
456  );
457  }
458  }
459 
460  ARMARX_DEBUG << "Finished updating the " << checked_obstacles << " managed obstacles (removed: " << remove_obstacles.size() << ", updated: " << updated_obstacles << "). " << published_obstacles << " of them should be published. The whole operation took " << (IceUtil::Time::now() - started).toMilliSeconds() << "ms";
461  }
462 
463  void DynamicObstacleManager::visualize_obstacle(viz::Layer& layer, const ManagedObstaclePtr& o, const armarx::DrawColor& color, double pos_z, bool text)
464  {
465  // Visualize ellipses.m_obstacle_manager_layer_name
466  Eigen::Vector3f dim(o->m_obstacle.axisLengthX * 2,
467  o->m_obstacle.axisLengthY * 2,
468  o->m_obstacle.axisLengthZ * 2);
469 
470  const std::string name = o->m_obstacle.name;
471 
472  layer.add(viz::Box(name).position(Eigen::Vector3f(o->m_obstacle.posX, o->m_obstacle.posY, pos_z))
473  .orientation(Eigen::AngleAxisf(o->m_obstacle.yaw, Eigen::Vector3f::UnitZ()).toRotationMatrix())
474  .size(dim).color(color.r, color.g, color.b, color.a));
475 
476  }
477 
478 
479  armarx::PropertyDefinitionsPtr DynamicObstacleManager::createPropertyDefinitions()
480  {
481  PropertyDefinitionsPtr defs{new ComponentPropertyDefinitions{getConfigIdentifier()}};
482 
483  defs->component(m_obstacle_detection, "PlatformObstacleAvoidance", "ObstacleAvoidanceName", "The name of the used obstacle avoidance interface");
484 
485  defs->optional(m_min_coverage_of_obstacles, "MinSampleRatioPerEllipsis", "Minimum percentage of samples which have to be in an elllipsis to be considered as known obsacle");
486  defs->optional(m_min_coverage_of_line_samples_in_obstacle, "MinSampleRatioPerLineSegment", "Minimum percentage of samples which have to be in an elllipsis to be considered as known obsacle");
487  defs->optional(m_min_size_of_obstacles, "MinObstacleSize", "The minimal obstacle size in mm.");
488  defs->optional(m_max_size_of_obstacles, "MaxObstacleSize", "The maximal obstacle size in mm.");
489  defs->optional(m_min_length_of_lines, "MinLengthOfLines", "Minimum length of lines in mm");
490  defs->optional(m_max_length_of_lines, "MaxLengthOfLines", "Maximum length of lines in mm");
491  defs->optional(m_decay_after_ms, "MaxObstacleValue", "Maximum value for the obstacles");
492  defs->optional(m_min_value_for_accepting, "MinObstacleValueForAccepting", "Minimum value for the obstacles to get accepted");
493  defs->optional(m_periodic_task_interval, "UpdateInterval", "The interval to check the obstacles");
494  defs->optional(m_thickness_of_lines, "LineThickness", "The thickness of line obstacles");
495  defs->optional(m_security_margin_for_obstacles, "ObstacleSecurityMargin", "Security margin of ellipsis obstacles");
496  defs->optional(m_security_margin_for_lines, "LineSecurityMargin", "Security margin of line obstacles");
497  defs->optional(m_remove_enabled, "EnableRemove", "Delete Obstacles when value < 0");
498  defs->optional(m_only_visualize, "OnlyVisualizeObstacles", "Connection to obstacle avoidance");
499  defs->optional(m_allow_spwan_inside, "AllowInRobotSpawning", "Allow obstacles to spawn inside the robot");
500 
501  return defs;
502  }
503 }
TIMING_START
#define TIMING_START(name)
Definition: TimeUtil.h:280
Eigen
Definition: Elements.h:36
time.h
TIMING_END
#define TIMING_END(name)
Definition: TimeUtil.h:296
DynamicObstacleManager.h
Pose.h
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::viz::Layer::add
void add(ElementT const &element)
Definition: Layer.h:29
armarx::PropertyDefinitionContainer::component
void component(IceInternal::ProxyHandle< PropertyType > &setter, const std::string &default_name="", const std::string &property_name="", const std::string &description="")
Definition: PropertyDefinitionContainer.h:404
clamp
double clamp(double x, double a, double b)
Definition: point.hpp:125
M_PI
#define M_PI
Definition: MathTools.h:17
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
armarx::viz::ElementOps::orientation
DerivedT & orientation(Eigen::Quaternionf const &ori)
Definition: ElementOps.h:140
armarx::viz::Box
Definition: Elements.h:51
max
T max(T t1, T t2)
Definition: gdiam.h:48
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:40
Component.h
armarx::DynamicObstacleManager::default_name
static const std::string default_name
Definition: DynamicObstacleManager.h:91
Ice
Definition: DBTypes.cpp:64
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:70
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::viz::Box::size
Box & size(Eigen::Vector3f const &s)
Definition: Elements.h:55
armarx::viz::ElementOps::color
DerivedT & color(Color color)
Definition: ElementOps.h:195
armarx::PeriodicTask
Definition: ArmarXManager.h:70
min
T min(T t1, T t2)
Definition: gdiam.h:42
armarx::viz::Layer
Definition: Layer.h:12
armarx::ManagedObstacle
Definition: ManagedObstacle.h:49
armarx::ManagedObstaclePtr
std::shared_ptr< ManagedObstacle > ManagedObstaclePtr
Definition: ManagedObstacle.h:46
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28