5 #include <SimoxUtility/algorithm/apply.hpp>
6 #include <SimoxUtility/json/json.hpp>
7 #include <VirtualRobot/MathTools.h>
8 #include <VirtualRobot/Robot.h>
9 #include <VirtualRobot/SceneObjectSet.h>
19 #include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
27 #include <teb_local_planner/homotopy_class_planner.h>
35 LocalPlanner(ctx), params(i_params), scene(ctx), obstManager(teb_obstacles)
44 auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(
49 hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
51 cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(),
nullptr);
62 hcp_->setCostmap(&teb_costmap.value());
68 TimedElasticBands::readDefaultConfig(arondto::TimedElasticBandsParams&
target)
71 "local_planner_config/TimedElasticBands/default.json");
72 const std::filesystem::path file = configPath.toSystemPath();
74 ARMARX_CHECK(std::filesystem::is_regular_file(file)) << file;
76 ARMARX_INFO <<
"Loading config from file `" << file <<
"`.";
77 std::ifstream ifs{file};
79 nlohmann::json jsonConfig;
85 target.read(reader, jsonConfig);
88 std::optional<LocalPlannerResult>
95 currentPose.translation(),
params.
cfg.planning_distance * 1000);
97 const teb_local_planner::TimedElasticBand globalPath =
conv::toRos(prunedGoal);
98 teb_globalPath = globalPath.poses();
99 hcp_->setGlobalPath(&teb_globalPath);
101 const teb_local_planner::PoseSE2 start =
conv::toRos(currentPose);
102 const teb_local_planner::PoseSE2 end =
103 conv::toRos(prunedGoal.points().back().waypoint.pose);
113 success = hcp_->plan(start, end, &velocity_start, !planToDest);
117 hcp_->clearPlanner();
124 hcp_->clearPlanner();
129 if (hcp_->hasDiverged())
131 hcp_->clearPlanner();
136 if (hcp_->getTrajectoryContainer().empty())
138 hcp_->clearPlanner();
143 ARMARX_VERBOSE <<
"Planned successfully (found " << hcp_->getTrajectoryContainer().size()
151 auto layer =
arviz.value().layer(
"local_planner_path_alternatives");
154 int bestTebIdx = hcp_->bestTebIdx();
155 for (
const auto& teb : hcp_->getTrajectoryContainer())
162 const std::vector<Eigen::Vector3f> points =
163 simox::alg::apply(trajectory.
points(),
165 { return pt.pose.translation(); });
168 .color(simox::Color::gray()));
172 arviz.value().commit(layer);
175 return {{.trajectory = best}};
179 TimedElasticBands::fillObstacles()
187 visLayer =
arviz.value().layer(
"local_planner_obstacles");
195 for (
const auto& obst : scene.
staticScene.value().objects->getCollisionModels())
203 for (
const auto& obst : scene.
dynamicScene.value().humans)
208 for (
const auto& obst : scene.
dynamicScene->laserScannerFeatures)
216 arviz.value().commit(visLayer);
224 TimedElasticBands::setTebCostmap()
231 if (not scene.
staticScene->distanceToObstaclesCostmap.has_value())
236 const algorithms::Costmap& navigationCostmap =
237 scene.
staticScene->distanceToObstaclesCostmap.value();
238 teb_costmap.emplace(
conv::toRos(navigationCostmap));