TimedElasticBands.h
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  * @author Fabian Reister ( fabian dot reister at kit dot edu )
17  * @author Christian R. G. Dreher ( c dot dreher at kit dot edu )
18  * @date 2021
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #pragma once
24 
25 #include <optional>
26 #include <string>
27 
33 #include <armarx/navigation/local_planning/aron/TimedElasticBands.aron.generated.h>
34 
35 #include <teb_local_planner/homotopy_class_planner.h>
36 #include <teb_local_planner/teb_config.h>
37 
39 {
40  class TimedElasticBands : virtual public LocalPlanner
41  {
42  public:
44 
45  TimedElasticBands(const Params& params, const core::Scene& scene);
46  ~TimedElasticBands() override = default;
47 
48  void init(const core::GlobalTrajectory& initialTrajectory);
49 
50  std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) override;
51 
52  private:
53  void readConfig(arondto::TimedElasticBandsParams& target, const std::string& robotName);
54  void fillObstacles();
55  void setTebCostmap();
56 
57  protected:
59 
60  private:
61  const core::Scene& scene;
62 
63  teb_local_planner::TebConfig cfg_;
64  teb_local_planner::ObstContainer teb_obstacles;
65  TebObstacleManager obstManager;
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};
69  };
70 } // namespace armarx::navigation::local_planning
armarx::navigation::core::GlobalTrajectory
Definition: Trajectory.h:70
armarx::navigation::local_planning::TimedElasticBands::~TimedElasticBands
~TimedElasticBands() override=default
LocalPlanner.h
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:668
armarx::navigation::local_planning::TimedElasticBands::TimedElasticBands
TimedElasticBands(const Params &params, const core::Scene &scene)
Definition: TimedElasticBands.cpp:53
TimedElasticBandsParams.h
armarx::navigation::local_planning
This file is part of ArmarX.
Definition: fwd.h:35
armarx::navigation::local_planning::TimedElasticBands
Definition: TimedElasticBands.h:40
armarx::navigation::local_planning::TimedElasticBands::init
void init(const core::GlobalTrajectory &initialTrajectory)
armarx::navigation::local_planning::TimedElasticBandsParams
Definition: TimedElasticBandsParams.h:34
armarx::navigation::local_planning::TebObstacleManager
Definition: TebObstacleManager.h:36
armarx::navigation::core::Scene
Definition: types.h:60
armarx::navigation::local_planning::TimedElasticBands::plan
std::optional< LocalPlannerResult > plan(const core::GlobalTrajectory &goal) override
Definition: TimedElasticBands.cpp:128
armarx::navigation::local_planning::LocalPlanner
Definition: LocalPlanner.h:53
armarx::navigation::local_planning::TimedElasticBands::params
Params params
Definition: TimedElasticBands.h:58
Trajectory.h
types.h
TebObstacleManager.h