37 #include <VirtualRobot/Robot.h>
38 #include <SimoxUtility/json.h>
39 #include <SimoxUtility/math/convert.h>
42 #include <Ice/Current.h>
45 #include <DynamicObstacleAvoidance/Modulation.hpp>
46 #include <DynamicObstacleAvoidance/Obstacle/Ellipsoid.hpp>
47 #include <DynamicObstacleAvoidance/Utils/Plotting/PlottingTools.hpp>
48 namespace doa = DynamicObstacleAvoidance;
61 std::shared_ptr<doa::Obstacle>
62 create_doa_obstacle(
const armarx::obstacledetection::Obstacle& obstacle)
64 Eigen::Vector3d pos(obstacle.posX, obstacle.posY, obstacle.posZ);
67 std::shared_ptr<doa::Ellipsoid> obstacle_ptr =
68 std::make_shared<doa::Ellipsoid>(obstacle.name,
70 Eigen::Array3d(obstacle.safetyMarginX / 1000,
71 obstacle.safetyMarginY / 1000,
72 obstacle.safetyMarginZ / 1000));
74 obstacle_ptr->set_axis_lengths(Eigen::Array3d(obstacle.axisLengthX,
76 obstacle.axisLengthZ) / 1000);
77 obstacle_ptr->set_reference_position(Eigen::Vector3d(obstacle.refPosX,
79 obstacle.refPosZ) / 1000);
80 obstacle_ptr->set_curvature_factor(Eigen::Array3d(obstacle.curvatureX,
82 obstacle.curvatureZ));
94 from_json(
const nlohmann::json& j, armarx::obstacledetection::Obstacle& obstacle)
96 j.at(
"name").get_to(obstacle.name);
97 j.at(
"posX").get_to(obstacle.posX);
98 j.at(
"posY").get_to(obstacle.posY);
99 if (j.find(
"posZ") != j.end())
101 j.at(
"posZ").get_to(obstacle.posZ);
103 j.at(
"yaw").get_to(obstacle.yaw);
104 j.at(
"axisLengthX").get_to(obstacle.axisLengthX);
105 j.at(
"axisLengthY").get_to(obstacle.axisLengthY);
106 if (j.find(
"axisLengthZ") != j.end())
108 j.at(
"axisLengthZ").get_to(obstacle.axisLengthZ);
110 j.at(
"refPosX").get_to(obstacle.refPosX);
111 j.at(
"refPosY").get_to(obstacle.refPosY);
112 if (j.find(
"refPosZ") != j.end())
114 j.at(
"refPosZ").get_to(obstacle.refPosZ);
116 if (j.find(
"safetyMarginX") != j.end())
118 j.at(
"safetyMarginX").get_to(obstacle.safetyMarginX);
120 if (j.find(
"safetyMarginY") != j.end())
122 j.at(
"safetyMarginY").get_to(obstacle.safetyMarginY);
124 if (j.find(
"safetyMarginZ") != j.end())
126 j.at(
"safetyMarginZ").get_to(obstacle.safetyMarginZ);
128 if (j.find(
"curvatureX") != j.end())
130 j.at(
"curvatureX").get_to(obstacle.curvatureX);
132 if (j.find(
"curvatureY") != j.end())
134 j.at(
"curvatureY").get_to(obstacle.curvatureY);
136 if (j.find(
"curvatureZ") != j.end())
138 j.at(
"curvatureZ").get_to(obstacle.curvatureZ);
152 m_doa.cfg.only_2d =
true;
153 m_doa.cfg.aggregated =
true;
154 m_doa.cfg.agent_safety_margin = 0;
155 m_doa.cfg.local_modulation =
false;
156 m_doa.cfg.repulsion =
true;
157 m_doa.cfg.planar_modulation =
false;
158 m_doa.cfg.critical_distance = 1.0;
159 m_doa.cfg.weight_power = 2.0;
168 m_buf.needs_env_update =
false;
170 m_doa.env.set_aggregated(m_doa.cfg.aggregated);
172 if (not m_doa.load_obstacles_from_file.empty())
174 const std::filesystem::path scene_obstacles_path =
176 std::ifstream ifs(scene_obstacles_path);
177 nlohmann::json j = nlohmann::json::parse(ifs);
179 std::vector<obstacledetection::Obstacle> obstacles = j;
180 for (obstacledetection::Obstacle& obstacle : obstacles)
182 if (m_doa.cfg.only_2d)
185 obstacle.axisLengthZ = 0;
186 obstacle.refPosZ = 0;
187 obstacle.safetyMarginZ = 0;
188 obstacle.curvatureZ = 1;
191 sanity_check_obstacle(obstacle);
193 m_doa.env.add_obstacle(::create_doa_obstacle(obstacle));
199 writeDebugPlots(
"doa_upstart");
214 &DSObstacleAvoidance::run_visualization, m_vis.task_interval);
218 if (m_watchdog.enabled)
222 &DSObstacleAvoidance::run_watchdog, m_watchdog.task_interval);
223 m_watchdog.task->start();
240 if (m_watchdog.enabled)
242 m_watchdog.task->stop();
266 armarx::dsobstacleavoidance::Config
275 const armarx::obstacledetection::Obstacle& obstacle,
278 ARMARX_DEBUG <<
"Adding/updating obstacle: " << obstacle.name <<
".";
280 std::unique_lock l{m_buf.mutex};
282 sanity_check_obstacle(obstacle);
285 update.time = IceUtil::Time::now();
286 update.name = obstacle.name;
289 m_buf.update_log.push_back(
update);
290 m_buf.obstacles[obstacle.name] = obstacle;
291 m_buf.needs_env_update =
true;
293 ARMARX_DEBUG <<
"Added/updated obstacle: " << obstacle.name <<
".";
300 ARMARX_DEBUG <<
"Removing obstacle: " << obstacle_name <<
".";
302 std::unique_lock l{m_buf.mutex};
305 update.time = IceUtil::Time::now();
306 update.name = obstacle_name;
307 update.type = buffer::update_type::removal;
309 m_buf.update_log.push_back(
update);
310 m_buf.needs_env_update =
true;
312 ARMARX_DEBUG <<
"Removed obstacle: " << obstacle_name <<
".";
316 std::vector<armarx::obstacledetection::Obstacle>
320 std::shared_lock l{m_doa.mutex};
322 std::vector<obstacledetection::Obstacle> obstacle_list;
324 for (
auto& [doa_name, doa_obstacle] : m_doa.env)
327 std::shared_ptr<doa::Ellipsoid> doa_ellipsoid = std::dynamic_pointer_cast<doa::Ellipsoid>(doa_obstacle);
328 obstacledetection::Obstacle obstacle;
330 obstacle.name = doa_name;
331 obstacle.posX = doa_ellipsoid->get_position()(0) * 1000;
332 obstacle.posY = doa_ellipsoid->get_position()(1) * 1000;
333 obstacle.posZ = doa_ellipsoid->get_position()(2) * 1000;
334 obstacle.yaw = simox::math::mat3f_to_rpy(doa_ellipsoid->get_orientation().toRotationMatrix().cast<
float>()).z();
335 obstacle.axisLengthX = doa_ellipsoid->get_axis_lengths(0) * 1000;
336 obstacle.axisLengthY = doa_ellipsoid->get_axis_lengths(1) * 1000;
337 obstacle.axisLengthZ = doa_ellipsoid->get_axis_lengths(2) * 1000;
338 obstacle.refPosX = doa_ellipsoid->get_reference_position()(0) * 1000;
339 obstacle.refPosY = doa_ellipsoid->get_reference_position()(1) * 1000;
340 obstacle.refPosZ = doa_ellipsoid->get_reference_position()(2) * 1000;
341 obstacle.safetyMarginX = doa_ellipsoid->get_safety_margin()(0) * 1000;
342 obstacle.safetyMarginY = doa_ellipsoid->get_safety_margin()(1) * 1000;
343 obstacle.safetyMarginZ = doa_ellipsoid->get_safety_margin()(2) * 1000;
344 obstacle.curvatureX = doa_ellipsoid->get_curvature_factor()(0);
345 obstacle.curvatureY = doa_ellipsoid->get_curvature_factor()(1);
346 obstacle.curvatureZ = doa_ellipsoid->get_curvature_factor()(2);
349 obstacle_list.push_back(std::move(obstacle));
353 return obstacle_list;
359 const obstacleavoidance::Agent& agent,
364 std::shared_lock l{m_doa.mutex};
367 doa::Agent doa_agent{agent.safety_margin};
369 Eigen::Vector3d agent_global_position = agent.pos.cast<
double>() / 1000;
370 Eigen::Vector3d agent_velocity = agent.desired_vel.cast<
double>() / 1000;
372 if (m_doa.cfg.only_2d)
374 agent_global_position(2) = 0;
375 agent_velocity(2) = 0;
378 doa_agent.set_position(agent_global_position);
379 doa_agent.set_linear_velocity(agent_velocity);
383 Eigen::Vector3d modulated_vel = doa::Modulation::modulate_velocity(
386 m_doa.cfg.local_modulation,
388 m_doa.cfg.planar_modulation,
389 m_doa.cfg.critical_distance,
390 m_doa.cfg.weight_power);
393 modulated_vel *= 1000;
396 if (m_doa.cfg.only_2d)
398 modulated_vel(2) = 0;
403 return modulated_vel.cast<
float>();
411 std::lock_guard l2{m_vis.mutex};
412 std::lock_guard l{m_doa.mutex};
415 std::vector<buffer::update> update_log;
416 std::map<std::string, obstacledetection::Obstacle> obstacles;
418 std::lock_guard l{m_buf.mutex};
420 if (not m_buf.needs_env_update)
426 update_log = m_buf.update_log;
427 obstacles = m_buf.obstacles;
428 m_buf.update_log.clear();
429 m_buf.obstacles.clear();
430 m_buf.needs_env_update =
false;
431 m_buf.last_env_update = IceUtil::Time::now();
438 doa::Environment::iterator it = m_doa.env.find(
update.name);
442 case buffer::update_type::removal:
445 if (it != m_doa.env.end())
447 m_doa.env.erase(
update.name);
452 <<
"obstacle is unknown to the environment.";
458 if (it != m_doa.env.end())
461 m_doa.env.erase(
update.name);
468 const obstacledetection::Obstacle& obstacle = obstacles.at(
update.name);
469 m_doa.env.add_obstacle(::create_doa_obstacle(obstacle));
478 m_vis.needs_update =
true;
481 ARMARX_VERBOSE <<
"Updating environment with " << update_log.size() <<
" updates took "
490 std::shared_lock l{m_doa.mutex};
492 const std::string filename_annotated = getName() +
"_" +
filename;
493 ARMARX_DEBUG <<
"Writing debug plots to `/tmp/" << filename_annotated <<
".png`.";
495 const bool show =
false;
498 doa::PlottingTools::plot_configuration(m_doa.env.get_obstacle_list(), filename_annotated,
499 show, not m_doa.cfg.only_2d);
503 ARMARX_WARNING <<
"Tried to write debug plots but failed, probably because "
504 <<
"`python3-matplotlib` are not installed.";
510 armarx::DSObstacleAvoidance::sanity_check_obstacle(
511 const armarx::obstacledetection::Obstacle& obstacle)
514 ARMARX_DEBUG <<
"Sanity checking obstacle `" << obstacle.name <<
"`.";
516 const std::string curvature_error =
"Curvature must be greater than or equal to 1.";
517 const std::string z_comps_set_error =
"2D mode activated. Z-component values must not be set.";
523 if (m_doa.cfg.only_2d)
525 ARMARX_DEBUG <<
"Additionally sanity checking obstacle `" << obstacle.name
526 <<
"` for 2D compliance.";
537 armarx::DSObstacleAvoidance::run_visualization()
542 std::lock_guard l{m_vis.mutex};
543 if (not m_vis.needs_update)
548 Layer layer_obs = arviz.layer(
"obstacles");
549 Layer layer_sms = arviz.layer(
"safety_margins");
550 Layer layer_rps = arviz.layer(
"reference_points");
551 Layer layer_bbs = arviz.layer(
"bounding_boxes");
553 for (
const obstacledetection::Obstacle& obstacle : getObstacles())
558 if (obstacle.name ==
"human")
563 else if (not m_doa.cfg.only_2d)
569 const double safetyMarginZ = m_doa.cfg.only_2d ? 1 : obstacle.safetyMarginZ;
570 const double posZ = m_doa.cfg.only_2d ? 1 : obstacle.posZ;
571 const double refPosZ = m_doa.cfg.only_2d ? 1 : obstacle.refPosZ;
572 const double axisLengthZ = m_doa.cfg.only_2d ? 1 : obstacle.axisLengthZ;
575 obstacle.posX, obstacle.posY, posZ,
577 const Eigen::Vector3f dim(obstacle.axisLengthX, obstacle.axisLengthY, axisLengthZ);
578 const Eigen::Vector3f sm(obstacle.safetyMarginX, obstacle.safetyMarginY, safetyMarginZ);
579 const Eigen::Vector3f curv(obstacle.curvatureX, obstacle.curvatureY, obstacle.curvatureZ);
581 if (m_doa.cfg.only_2d)
586 .axisLengths(dim.head<2>())
588 .curvature(curv.head<2>())
593 .axisLengths((dim + sm).head<2>())
594 .height(dim(2) + sm(2))
595 .curvature(curv.head<2>())
608 .axisLengths(dim + sm)
613 layer_rps.
add(
Sphere{obstacle.name +
"_rp"}
614 .
position(Eigen::Vector3f(obstacle.refPosX, obstacle.refPosY, refPosZ))
618 layer_bbs.
add(
Box{obstacle.name +
"_bb"}
624 m_vis.needs_update =
false;
626 arviz.commit({layer_obs, layer_sms, layer_rps});
632 armarx::DSObstacleAvoidance::run_watchdog()
634 bool needs_env_update;
635 bool was_recently_updated;
637 std::unique_lock l{m_buf.mutex};
638 needs_env_update = m_buf.needs_env_update;
639 was_recently_updated = IceUtil::Time::now() - m_buf.last_env_update <= m_watchdog.threshold;
642 if (needs_env_update and not was_recently_updated)
645 << m_watchdog.threshold <<
". Have you forgotten to call "
646 <<
"`updateEnvironment()` after adding, updating or removing obstacles? "
647 <<
"Forcing update now.";
659 def->
optional(m_vis.enabled,
"visualize",
"Enable/disable visualization.");
660 def->optional(m_watchdog.enabled,
"udpate_watchdog",
"Run environment update watchdog.");
661 def->optional(m_doa.load_obstacles_from_file,
"load_obstacles_from",
662 "Path to JSON file to load initial obstacles from.");
665 def->optional(m_doa.cfg.only_2d,
"doa.only_2d",
"Only consider 2D.");
666 def->optional(m_doa.cfg.aggregated,
"doa.aggregated",
"Aggregated environment.");
667 def->optional(m_doa.cfg.agent_safety_margin,
"doa.agent_safety_margin",
"Agent safety margin.");
668 def->optional(m_doa.cfg.local_modulation,
"doa.local_modulation",
"Local modulation on/off.");
669 def->optional(m_doa.cfg.repulsion,
"doa.repulsion",
"Repulsion on/off.");
670 def->optional(m_doa.cfg.planar_modulation,
"doa.planar_modulation",
671 "Planar modulation on/off.");
672 def->optional(m_doa.cfg.critical_distance,
"doa.critical_distance",
"Critical distance.");
673 def->optional(m_doa.cfg.weight_power,
"doa.weight_power",
"Weight power");