dijkstra_mesh_planner.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * authors:
34  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
35  *
36  */
37 
38 #ifndef MESH_NAVIGATION__dijkstra_mesh_planner_H
39 #define MESH_NAVIGATION__DIJKSTRA_MESH_PLANNER_H
40 
42 #include <mbf_msgs/GetPathResult.h>
43 #include <mesh_map/mesh_map.h>
44 #include <dijkstra_mesh_planner/DijkstraMeshPlannerConfig.h>
45 #include <nav_msgs/Path.h>
46 
48 {
50 {
51 public:
53 
55 
59  virtual ~DijkstraMeshPlanner();
60 
87  virtual uint32_t makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
88  double tolerance, std::vector<geometry_msgs::PoseStamped>& plan, double& cost,
89  std::string& message);
90 
97  virtual bool cancel();
98 
107  virtual bool initialize(const std::string& name, const boost::shared_ptr<mesh_map::MeshMap>& mesh_map_ptr);
108 
115 
116 protected:
128  uint32_t dijkstra(const mesh_map::Vector& start, const mesh_map::Vector& goal, std::list<lvr2::VertexHandle>& path);
129 
144  uint32_t dijkstra(const mesh_map::Vector& start, const mesh_map::Vector& goal,
145  const lvr2::DenseEdgeMap<float>& edge_weights, const lvr2::DenseVertexMap<float>& costs,
146  std::list<lvr2::VertexHandle>& path, lvr2::DenseVertexMap<float>& distances,
148 
152  void computeVectorMap();
153 
160  void reconfigureCallback(dijkstra_mesh_planner::DijkstraMeshPlannerConfig& cfg, uint32_t level);
161 
162 private:
163  // current map
165  // name of this plugin
166  std::string name;
167  // node handle
169  // true if the abort of the current planning was requested; else false
170  std::atomic_bool cancel_planning;
171  // publisher of resulting path
173  // publisher of resulting vector fiels
175  // publisher of per face vectorfield
177  // tf frame of the map
178  std::string map_frame;
179  // offset of maximum distance from goal position
181  // Server for Reconfiguration
184  dynamic_reconfigure::Server<dijkstra_mesh_planner::DijkstraMeshPlannerConfig>::CallbackType config_callback;
186  DijkstraMeshPlannerConfig config;
187 
188  // predecessors while wave propagation
190  // the face which is cut by line to the source
192  // stores the current vector map containing vectors pointing to the source
193  // (path goal)
195  // potential field or distance values to the source (path goal)
197 };
198 
199 } // namespace dijkstra_mesh_planner
200 
201 #endif // MESH_NAVIGATION__DIJKSTRA_MESH_PLANNER_H
dijkstra_mesh_planner::DijkstraMeshPlanner::mesh_map
mesh_map::MeshMap::Ptr mesh_map
Definition: dijkstra_mesh_planner.h:164
dijkstra_mesh_planner::DijkstraMeshPlanner::name
std::string name
Definition: dijkstra_mesh_planner.h:166
ros::Publisher
lvr2::BaseVector
boost::shared_ptr
dijkstra_mesh_planner::DijkstraMeshPlanner::cancel
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
Definition: dijkstra_mesh_planner.cpp:123
dijkstra_mesh_planner::DijkstraMeshPlanner::predecessors
lvr2::DenseVertexMap< lvr2::VertexHandle > predecessors
Definition: dijkstra_mesh_planner.h:189
dijkstra_mesh_planner::DijkstraMeshPlanner::DijkstraMeshPlanner
DijkstraMeshPlanner()
Definition: dijkstra_mesh_planner.cpp:48
lvr2::VectorMap
dijkstra_mesh_planner::DijkstraMeshPlanner::dijkstra
uint32_t dijkstra(const mesh_map::Vector &start, const mesh_map::Vector &goal, std::list< lvr2::VertexHandle > &path)
runs dijkstra path planning and stores the resulting distances and predecessors to the fields potenti...
Definition: dijkstra_mesh_planner.cpp:193
dijkstra_mesh_planner::DijkstraMeshPlanner::publish_face_vectors
bool publish_face_vectors
Definition: dijkstra_mesh_planner.h:176
dijkstra_mesh_planner::DijkstraMeshPlanner::cutting_faces
lvr2::DenseVertexMap< lvr2::FaceHandle > cutting_faces
Definition: dijkstra_mesh_planner.h:191
dijkstra_mesh_planner::DijkstraMeshPlanner::vector_map
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
Definition: dijkstra_mesh_planner.h:194
dijkstra_mesh_planner::DijkstraMeshPlanner::map_frame
std::string map_frame
Definition: dijkstra_mesh_planner.h:178
mbf_mesh_core::MeshPlanner
dijkstra_mesh_planner::DijkstraMeshPlanner::getVectorMap
lvr2::DenseVertexMap< mesh_map::Vector > getVectorMap()
delivers vector field which has been generated during the latest planning
Definition: dijkstra_mesh_planner.cpp:154
dijkstra_mesh_planner::DijkstraMeshPlanner
Definition: dijkstra_mesh_planner.h:49
dijkstra_mesh_planner::DijkstraMeshPlanner::computeVectorMap
void computeVectorMap()
calculates the vector field based on the current predecessors map and stores it to the vector_map fie...
Definition: dijkstra_mesh_planner.cpp:171
dijkstra_mesh_planner::DijkstraMeshPlanner::~DijkstraMeshPlanner
virtual ~DijkstraMeshPlanner()
Destructor.
Definition: dijkstra_mesh_planner.cpp:52
dijkstra_mesh_planner::DijkstraMeshPlanner::publish_vector_field
bool publish_vector_field
Definition: dijkstra_mesh_planner.h:174
dijkstra_mesh_planner::DijkstraMeshPlanner::reconfigureCallback
void reconfigureCallback(dijkstra_mesh_planner::DijkstraMeshPlannerConfig &cfg, uint32_t level)
gets called on new incoming reconfigure parameters
Definition: dijkstra_mesh_planner.cpp:159
dijkstra_mesh_planner
Definition: dijkstra_mesh_planner.h:47
dijkstra_mesh_planner::DijkstraMeshPlanner::cancel_planning
std::atomic_bool cancel_planning
Definition: dijkstra_mesh_planner.h:170
dijkstra_mesh_planner::DijkstraMeshPlanner::reconfigure_server_ptr
boost::shared_ptr< dynamic_reconfigure::Server< dijkstra_mesh_planner::DijkstraMeshPlannerConfig > > reconfigure_server_ptr
Definition: dijkstra_mesh_planner.h:183
dijkstra_mesh_planner::DijkstraMeshPlanner::first_config
bool first_config
Definition: dijkstra_mesh_planner.h:185
mesh_planner.h
dijkstra_mesh_planner::DijkstraMeshPlanner::goal_dist_offset
float goal_dist_offset
Definition: dijkstra_mesh_planner.h:180
mesh_map.h
dijkstra_mesh_planner::DijkstraMeshPlanner::potential
lvr2::DenseVertexMap< float > potential
Definition: dijkstra_mesh_planner.h:196
dijkstra_mesh_planner::DijkstraMeshPlanner::initialize
virtual bool initialize(const std::string &name, const boost::shared_ptr< mesh_map::MeshMap > &mesh_map_ptr)
initializes this planner with the given plugin name and map
Definition: dijkstra_mesh_planner.cpp:129
dijkstra_mesh_planner::DijkstraMeshPlanner::path_pub
ros::Publisher path_pub
Definition: dijkstra_mesh_planner.h:172
dijkstra_mesh_planner::DijkstraMeshPlanner::config
DijkstraMeshPlannerConfig config
Definition: dijkstra_mesh_planner.h:186
dijkstra_mesh_planner::DijkstraMeshPlanner::config_callback
dynamic_reconfigure::Server< dijkstra_mesh_planner::DijkstraMeshPlannerConfig >::CallbackType config_callback
Definition: dijkstra_mesh_planner.h:184
dijkstra_mesh_planner::DijkstraMeshPlanner::private_nh
ros::NodeHandle private_nh
Definition: dijkstra_mesh_planner.h:168
dijkstra_mesh_planner::DijkstraMeshPlanner::makePlan
virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message)
Given a goal pose in the world, compute a plan.
Definition: dijkstra_mesh_planner.cpp:56
dijkstra_mesh_planner::DijkstraMeshPlanner::Ptr
boost::shared_ptr< dijkstra_mesh_planner::DijkstraMeshPlanner > Ptr
Definition: dijkstra_mesh_planner.h:52
ros::NodeHandle


dijkstra_mesh_planner
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:54