wave_front_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__MESH_PLANNER_H
39 #define MESH_NAVIGATION__MESH_PLANNER_H
40 
42 #include <mbf_msgs/GetPathResult.h>
43 #include <mesh_map/mesh_map.h>
44 #include <wave_front_planner/WaveFrontPlannerConfig.h>
45 #include <nav_msgs/Path.h>
46 
48 {
50 {
51 public:
53 
58 
62  virtual ~WaveFrontPlanner();
63 
74  virtual uint32_t makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
75  double tolerance, std::vector<geometry_msgs::PoseStamped>& plan, double& cost,
76  std::string& message);
77 
82  virtual bool cancel();
83 
90  virtual bool initialize(const std::string& name, const boost::shared_ptr<mesh_map::MeshMap>& mesh_map_ptr);
91 
92 protected:
93 
101  uint32_t waveFrontPropagation(const mesh_map::Vector& start, const mesh_map::Vector& goal,
102  std::list<std::pair<mesh_map::Vector, lvr2::FaceHandle>>& path);
103 
116  uint32_t waveFrontPropagation(const mesh_map::Vector& start, const mesh_map::Vector& goal,
117  const lvr2::DenseEdgeMap<float>& edge_weights, const lvr2::DenseVertexMap<float>& costs,
118  std::list<std::pair<mesh_map::Vector, lvr2::FaceHandle>>& path,
119  lvr2::DenseVertexMap<float>& distances,
121 
131  inline bool waveFrontUpdateWithS(lvr2::DenseVertexMap<float>& distances,
132  const lvr2::DenseEdgeMap<float>& edge_weights, const lvr2::VertexHandle& v1,
133  const lvr2::VertexHandle& v2, const lvr2::VertexHandle& v3);
134 
135 
145  inline bool waveFrontUpdate(lvr2::DenseVertexMap<float>& distances, const lvr2::DenseEdgeMap<float>& edge_weights,
146  const lvr2::VertexHandle& v1, const lvr2::VertexHandle& v2, const lvr2::VertexHandle& v3);
147 
151  void computeVectorMap();
152 
156  void reconfigureCallback(wave_front_planner::WaveFrontPlannerConfig& cfg, uint32_t level);
157 
158 private:
159 
162 
164  std::string name;
165 
168 
170  std::atomic_bool cancel_planning;
171 
174 
177 
180 
182  std::string map_frame;
183 
186 
189 
191  dynamic_reconfigure::Server<wave_front_planner::WaveFrontPlannerConfig>::CallbackType config_callback;
192 
195 
197  WaveFrontPlannerConfig config;
198 
201 
204 
207 
210 
213 };
214 
215 } // namespace wave_front_planner
216 
217 #endif // MESH_NAVIGATION__WAVE_FRONT_PLANNER_H
wave_front_planner::WaveFrontPlanner::config_callback
dynamic_reconfigure::Server< wave_front_planner::WaveFrontPlannerConfig >::CallbackType config_callback
dynamic reconfigure callback function binding
Definition: wave_front_planner.h:191
ros::Publisher
lvr2::BaseVector
boost::shared_ptr
wave_front_planner::WaveFrontPlanner::first_config
bool first_config
indicates if dynamic reconfigure has been called the first time
Definition: wave_front_planner.h:194
wave_front_planner::WaveFrontPlanner::private_nh
ros::NodeHandle private_nh
the private node handle with the user defined namespace (name)
Definition: wave_front_planner.h:167
wave_front_planner::WaveFrontPlanner::cancel_planning
std::atomic_bool cancel_planning
flag if cancel has been requested
Definition: wave_front_planner.h:170
wave_front_planner::WaveFrontPlanner::WaveFrontPlanner
WaveFrontPlanner()
Constructor.
Definition: wave_front_planner.cpp:53
wave_front_planner::WaveFrontPlanner::predecessors
lvr2::DenseVertexMap< lvr2::VertexHandle > predecessors
predecessors while wave propagation
Definition: wave_front_planner.h:203
wave_front_planner::WaveFrontPlanner::waveFrontPropagation
uint32_t waveFrontPropagation(const mesh_map::Vector &start, const mesh_map::Vector &goal, std::list< std::pair< mesh_map::Vector, lvr2::FaceHandle >> &path)
Computes a wavefront propagation from the start until it reached the goal.
Definition: wave_front_planner.cpp:207
wave_front_planner::WaveFrontPlanner::config
WaveFrontPlannerConfig config
the current dynamic reconfigure planner configuration
Definition: wave_front_planner.h:197
wave_front_planner::WaveFrontPlanner::potential
lvr2::DenseVertexMap< float > potential
potential field / scalar distance field to the seed
Definition: wave_front_planner.h:212
wave_front_planner::WaveFrontPlanner::reconfigureCallback
void reconfigureCallback(wave_front_planner::WaveFrontPlannerConfig &cfg, uint32_t level)
Dynamic reconfigure callback.
Definition: wave_front_planner.cpp:158
lvr2::VectorMap
wave_front_planner::WaveFrontPlanner::vector_map
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
stores the current vector map containing vectors pointing to the seed
Definition: wave_front_planner.h:209
wave_front_planner::WaveFrontPlanner::map_frame
std::string map_frame
the map coordinate frame / system id
Definition: wave_front_planner.h:182
wave_front_planner::WaveFrontPlanner::cutting_faces
lvr2::DenseVertexMap< lvr2::FaceHandle > cutting_faces
the face which is cut by the computed line to the source
Definition: wave_front_planner.h:206
wave_front_planner::WaveFrontPlanner::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)
Compute a continuous vector field and geodesic path on the mesh's surface.
Definition: wave_front_planner.cpp:61
mbf_mesh_core::MeshPlanner
wave_front_planner::WaveFrontPlanner::waveFrontUpdateWithS
bool waveFrontUpdateWithS(lvr2::DenseVertexMap< float > &distances, const lvr2::DenseEdgeMap< float > &edge_weights, const lvr2::VertexHandle &v1, const lvr2::VertexHandle &v2, const lvr2::VertexHandle &v3)
Definition: wave_front_planner.cpp:214
lvr2::VertexHandle
wave_front_planner::WaveFrontPlanner::computeVectorMap
void computeVectorMap()
Computes the vector field in a post processing. It rotates the predecessor edges by the stored angles...
Definition: wave_front_planner.cpp:170
wave_front_planner::WaveFrontPlanner::name
std::string name
the user defined plugin name
Definition: wave_front_planner.h:164
wave_front_planner::WaveFrontPlanner::direction
lvr2::DenseVertexMap< float > direction
theta angles to the source of the wave front propagation
Definition: wave_front_planner.h:200
wave_front_planner::WaveFrontPlanner::goal_dist_offset
float goal_dist_offset
an offset that determines how far beyond the goal (robot's position) is propagated.
Definition: wave_front_planner.h:185
wave_front_planner::WaveFrontPlanner::initialize
virtual bool initialize(const std::string &name, const boost::shared_ptr< mesh_map::MeshMap > &mesh_map_ptr)
Initializes the planner plugin with a user configured name and a shared pointer to the mesh map.
Definition: wave_front_planner.cpp:132
wave_front_planner::WaveFrontPlanner::publish_face_vectors
bool publish_face_vectors
whether to also publish direction vectors at the triangle centers
Definition: wave_front_planner.h:179
wave_front_planner
Definition: wave_front_planner.h:47
wave_front_planner::WaveFrontPlanner
Definition: wave_front_planner.h:49
wave_front_planner::WaveFrontPlanner::publish_vector_field
bool publish_vector_field
whether to publish the vector field or not
Definition: wave_front_planner.h:176
wave_front_planner::WaveFrontPlanner::waveFrontUpdate
bool waveFrontUpdate(lvr2::DenseVertexMap< float > &distances, const lvr2::DenseEdgeMap< float > &edge_weights, const lvr2::VertexHandle &v1, const lvr2::VertexHandle &v2, const lvr2::VertexHandle &v3)
Definition: wave_front_planner.cpp:334
mesh_planner.h
wave_front_planner::WaveFrontPlanner::cancel
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
Definition: wave_front_planner.cpp:126
mesh_map.h
wave_front_planner::WaveFrontPlanner::path_pub
ros::Publisher path_pub
publisher for the backtracked path
Definition: wave_front_planner.h:173
wave_front_planner::WaveFrontPlanner::Ptr
boost::shared_ptr< wave_front_planner::WaveFrontPlanner > Ptr
Definition: wave_front_planner.h:52
wave_front_planner::WaveFrontPlanner::~WaveFrontPlanner
virtual ~WaveFrontPlanner()
Destructor.
Definition: wave_front_planner.cpp:57
wave_front_planner::WaveFrontPlanner::reconfigure_server_ptr
boost::shared_ptr< dynamic_reconfigure::Server< wave_front_planner::WaveFrontPlannerConfig > > reconfigure_server_ptr
shared pointer to dynamic reconfigure server
Definition: wave_front_planner.h:188
wave_front_planner::WaveFrontPlanner::mesh_map
mesh_map::MeshMap::Ptr mesh_map
shared pointer to the mesh map
Definition: wave_front_planner.h:161
ros::NodeHandle


wave_front_planner
Author(s): Sebastian Pütz
autogenerated on Mon Jan 4 2021 03:44:17