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