TimedElasticBands.cpp
Go to the documentation of this file.
1 #include "TimedElasticBands.h"
2 
3 #include <optional>
4 
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>
10 
13 
15 
19 #include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
24 // #include <teb_local_planner/extension/obstacles/EllipseObstacle.h>
26 
27 #include <teb_local_planner/homotopy_class_planner.h>
28 
30 {
31 
32  // TimedElasticBands
33 
35  LocalPlanner(ctx), params(i_params), scene(ctx), obstManager(teb_obstacles)
36  {
37  //TODO (SALt): find proper place to init with default config
38  if (true)
39  {
40  readDefaultConfig(params.cfg);
41  }
42  toTebCfg(params.cfg, cfg_);
43 
44  auto robot_model = boost::make_shared<teb_local_planner::CircularRobotFootprint>(
45  params.cfg.robot_footprint_radius);
46 
47  ARMARX_VERBOSE << "Robot footprint is " << params.cfg.robot_footprint_radius << "m";
48 
49  hcp_ = std::make_unique<teb_local_planner::HomotopyClassPlanner>();
50  hcp_->initialize(
51  cfg_, &teb_obstacles, robot_model, teb_local_planner::TebVisualizationPtr(), nullptr);
52  //set member teb_costmap
53  setTebCostmap();
54  if (teb_costmap)
55  {
56  ARMARX_INFO << "Costmap available.";
57  // TODO: where to put all the parameters
58  const human::ExponentialPenaltyModel penalty{
59  .minDistance = 0.5, .epsilon = 0, .exponent = 1.2};
60 
61  teb_costmap->setPenaltyModel(conv::toRos(penalty));
62  hcp_->setCostmap(&teb_costmap.value());
63  }
64  ros::Time::init(); // we have to init time before we can use the planner
65  }
66 
67  void
68  TimedElasticBands::readDefaultConfig(arondto::TimedElasticBandsParams& target)
69  {
70  const armarx::PackagePath configPath("armarx_navigation",
71  "local_planner_config/TimedElasticBands/default.json");
72  const std::filesystem::path file = configPath.toSystemPath();
73 
74  ARMARX_CHECK(std::filesystem::is_regular_file(file)) << file;
75 
76  ARMARX_INFO << "Loading config from file `" << file << "`.";
77  std::ifstream ifs{file};
78 
79  nlohmann::json jsonConfig;
80  ifs >> jsonConfig;
81 
82  ARMARX_INFO << "Reading config";
83 
85  target.read(reader, jsonConfig);
86  }
87 
88  std::optional<LocalPlannerResult>
90  {
91  const core::Pose currentPose{scene.robot->getGlobalPose()};
92 
93  // prune global trajectory
94  const auto& [prunedGoal, planToDest] = goal.getSubTrajectory(
95  currentPose.translation(), params.cfg.planning_distance * 1000); // [m] to [mm]
96 
97  const teb_local_planner::TimedElasticBand globalPath = conv::toRos(prunedGoal);
98  teb_globalPath = globalPath.poses();
99  hcp_->setGlobalPath(&teb_globalPath);
100 
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);
104 
105  geometry_msgs::Twist velocity_start = conv::toRos(scene.platformVelocity);
106 
107 
108  fillObstacles();
109 
110  bool success;
111  try
112  {
113  success = hcp_->plan(start, end, &velocity_start, !planToDest);
114  }
115  catch (...)
116  {
117  hcp_->clearPlanner();
118  ARMARX_ERROR << "Caugth exception while planning: " << GetHandledExceptionString();
119  return std::nullopt;
120  }
121 
122  if (!success)
123  {
124  hcp_->clearPlanner();
125  ARMARX_WARNING << deactivateSpam(5) << "Found trajectory is not feasible!";
126  return std::nullopt;
127  }
128 
129  if (hcp_->hasDiverged())
130  {
131  hcp_->clearPlanner();
132  ARMARX_WARNING << deactivateSpam(5) << "Planner has diverged!";
133  return std::nullopt;
134  }
135 
136  if (hcp_->getTrajectoryContainer().empty())
137  {
138  hcp_->clearPlanner();
139  ARMARX_INFO << deactivateSpam(5) << "Did not find any trajectory!";
140  return std::nullopt;
141  }
142 
143  ARMARX_VERBOSE << "Planned successfully (found " << hcp_->getTrajectoryContainer().size()
144  << " Trajectories)";
145 
146  core::LocalTrajectory best = conv::fromRos(hcp_->findBestTeb()->teb());
147 
148  // visualize path alternatives
149  if (arviz)
150  {
151  auto layer = arviz.value().layer("local_planner_path_alternatives");
152 
153  int i = 0;
154  int bestTebIdx = hcp_->bestTebIdx();
155  for (const auto& teb : hcp_->getTrajectoryContainer())
156  {
157  if (i == bestTebIdx)
158  {
159  continue;
160  }
161  const core::LocalTrajectory trajectory = conv::fromRos(teb->teb());
162  const std::vector<Eigen::Vector3f> points =
163  simox::alg::apply(trajectory.points(),
164  [](const core::LocalTrajectoryPoint& pt) -> Eigen::Vector3f
165  { return pt.pose.translation(); });
166  layer.add(viz::Path("path_alternative_" + std::to_string(i))
167  .points(points)
168  .color(simox::Color::gray()));
169  i++;
170  }
171 
172  arviz.value().commit(layer);
173  }
174 
175  return {{.trajectory = best}};
176  }
177 
178  void
179  TimedElasticBands::fillObstacles()
180  {
181  obstManager.clear();
182 
183  viz::Layer* visPtr = nullptr;
184  viz::Layer visLayer;
185  if (arviz)
186  {
187  visLayer = arviz.value().layer("local_planner_obstacles");
188  visPtr = &visLayer;
189  }
190 
191 
192  if (scene.staticScene)
193  {
194  ARMARX_CHECK(scene.staticScene.has_value());
195  for (const auto& obst : scene.staticScene.value().objects->getCollisionModels())
196  {
197  obstManager.addBoxObstacle(obst->getGlobalBoundingBox(), visPtr);
198  }
199  }
200  if (scene.dynamicScene)
201  {
202  ARMARX_CHECK(scene.dynamicScene.has_value());
203  for (const auto& obst : scene.dynamicScene.value().humans)
204  {
205  obstManager.addHumanObstacle(obst, visPtr);
206  }
207 
208  for (const auto& obst : scene.dynamicScene->laserScannerFeatures)
209  {
210  obstManager.addLaserScannerFeaturesObstacle(obst, visPtr);
211  }
212  }
213 
214  if (arviz)
215  {
216  arviz.value().commit(visLayer);
217  }
218 
219  ARMARX_VERBOSE << "TEB: added " << obstManager.size() << " obstacles";
220  }
221 
222  //export algorithms::Costmap to costmap type of teb local planner and provide costmap to planner
223  void
224  TimedElasticBands::setTebCostmap()
225  {
226  if (not scene.staticScene.has_value())
227  {
228  return;
229  }
230 
231  if (not scene.staticScene->distanceToObstaclesCostmap.has_value())
232  {
233  return;
234  }
235 
236  const algorithms::Costmap& navigationCostmap =
237  scene.staticScene->distanceToObstaclesCostmap.value();
238  teb_costmap.emplace(conv::toRos(navigationCostmap));
239  }
240 
241 } // namespace armarx::navigation::local_planning
armarx::navigation::core::GlobalTrajectory
Definition: Trajectory.h:68
armarx::navigation::core::Scene::robot
VirtualRobot::RobotPtr robot
Definition: types.h:78
TimedElasticBands.h
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
armarx::navigation::human::ExponentialPenaltyModel::minDistance
float minDistance
Definition: types.h:68
armarx::navigation::local_planning::TebObstacleManager::addBoxObstacle
void addBoxObstacle(const VirtualRobot::BoundingBox &bbox, viz::Layer *visLayer=nullptr)
Definition: TebObstacleManager.cpp:68
armarx::navigation::local_planning::LocalPlanner::arviz
std::optional< viz::ScopedClient > arviz
Definition: LocalPlanner.h:64
armarx::navigation::core::Scene::staticScene
std::optional< core::StaticScene > staticScene
Definition: types.h:75
armarx::navigation::core::Pose
Eigen::Isometry3f Pose
Definition: basic_types.h:31
NlohmannJSONReaderWithoutTypeCheck.h
LocalPlanner.h
armarx::navigation::human::ExponentialPenaltyModel
Definition: types.h:66
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:688
armarx::navigation::local_planning
This file is part of ArmarX.
Definition: fwd.h:35
armarx::navigation::conv::fromRos
Eigen::Vector3f fromRos(const Eigen::Vector2d &vec)
Definition: ros_conversions.cpp:30
aron_conversions_teb.h
armarx::navigation::core::LocalTrajectory::points
const std::vector< LocalTrajectoryPoint > & points() const
Definition: Trajectory.cpp:837
ARMARX_CHECK
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
Definition: ExpressionException.h:82
armarx::navigation::local_planning::TimedElasticBandsParams::cfg
arondto::TimedElasticBandsParams cfg
Definition: TimedElasticBandsParams.h:37
armarx::navigation::core::Scene::platformVelocity
core::Twist platformVelocity
Definition: types.h:79
armarx::navigation::core::LocalTrajectoryPoint
Definition: Trajectory.h:152
deactivateSpam
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition: Logging.cpp:72
armarx::GetHandledExceptionString
std::string GetHandledExceptionString()
Definition: Exception.cpp:147
armarx::navigation::core::GlobalTrajectory::getSubTrajectory
std::pair< GlobalTrajectory, bool > getSubTrajectory(const Position &point, const float distance) const
Project point onto the trajectory and return a new trajectory along the old one from that point for t...
Definition: Trajectory.cpp:287
armarx::aron::data::reader::NlohmannJSONReaderWithoutTypeCheck
Definition: NlohmannJSONReaderWithoutTypeCheck.h:35
armarx::navigation::local_planning::TimedElasticBandsParams
Definition: TimedElasticBandsParams.h:35
armarx::navigation::conv::toRos
Eigen::Vector2d toRos(const Eigen::Vector3f &vec)
Definition: ros_conversions.cpp:24
armarx::navigation::core::LocalTrajectory
Definition: Trajectory.h:167
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:40
core.h
armarx::navigation::core::Scene
Definition: types.h:71
armarx::navigation::core::Scene::dynamicScene
std::optional< core::DynamicScene > dynamicScene
Definition: types.h:76
armarx::navigation::local_planning::TebObstacleManager::clear
void clear()
Definition: TebObstacleManager.cpp:14
armarx::navigation::local_planning::TimedElasticBands::plan
std::optional< LocalPlannerResult > plan(const core::GlobalTrajectory &goal) override
Definition: TimedElasticBands.cpp:89
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::navigation::local_planning::TebObstacleManager::size
size_t size()
Definition: TebObstacleManager.cpp:21
armarx::navigation::local_planning::TebObstacleManager::addLaserScannerFeaturesObstacle
void addLaserScannerFeaturesObstacle(const memory::LaserScannerFeatures &features, viz::Layer *visLayer=nullptr)
Definition: TebObstacleManager.cpp:26
armarx::navigation::local_planning::toTebCfg
void toTebCfg(const arondto::TimedElasticBandsParams &dto, ::teb_local_planner::TebConfig &bo)
Definition: aron_conversions_teb.cpp:16
armarx::navigation::local_planning::TebObstacleManager::addHumanObstacle
void addHumanObstacle(const human::Human &human, viz::Layer *visLayer=nullptr)
Definition: TebObstacleManager.cpp:83
armarx::navigation::local_planning::LocalPlanner
Definition: LocalPlanner.h:53
eigen.h
Logging.h
armarx::navigation::local_planning::TimedElasticBands::params
Params params
Definition: TimedElasticBands.h:57
armarx::viz::Path
Definition: Path.h:31
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
Trajectory.h
armarx::PackagePath
Definition: PackagePath.h:55
armarx::viz::Layer
Definition: Layer.h:12
armarx::status::success
@ success
aron_conversions.h
armarx::navigation::local_planning::TimedElasticBands::TimedElasticBands
TimedElasticBands(const Params &params, const core::Scene &ctx)
Definition: TimedElasticBands.cpp:34
ros_conversions.h
PackagePath.h