33 #include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
35 #include <teb_local_planner/homotopy_class_planner.h>
36 #include <teb_local_planner/teb_config.h>
53 void readConfig(arondto::TimedElasticBandsParams&
target,
const std::string& robotName);
63 teb_local_planner::TebConfig cfg_;
64 teb_local_planner::ObstContainer teb_obstacles;
66 teb_local_planner::PoseSequence teb_globalPath;
67 std::optional<teb_local_planner::Costmap> teb_costmap;
68 std::unique_ptr<teb_local_planner::HomotopyClassPlanner> hcp_{
nullptr};