Go to the documentation of this file.
38 #ifndef MESH_NAVIGATION__MESH_PLANNER_H
39 #define MESH_NAVIGATION__MESH_PLANNER_H
42 #include <mbf_msgs/GetPathResult.h>
44 #include <wave_front_planner/WaveFrontPlannerConfig.h>
45 #include <nav_msgs/Path.h>
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);
102 std::list<std::pair<mesh_map::Vector, lvr2::FaceHandle>>& path);
118 std::list<std::pair<mesh_map::Vector, lvr2::FaceHandle>>& path,
191 dynamic_reconfigure::Server<wave_front_planner::WaveFrontPlannerConfig>::CallbackType
config_callback;
217 #endif // MESH_NAVIGATION__WAVE_FRONT_PLANNER_H
dynamic_reconfigure::Server< wave_front_planner::WaveFrontPlannerConfig >::CallbackType config_callback
dynamic reconfigure callback function binding
bool first_config
indicates if dynamic reconfigure has been called the first time
ros::NodeHandle private_nh
the private node handle with the user defined namespace (name)
std::atomic_bool cancel_planning
flag if cancel has been requested
WaveFrontPlanner()
Constructor.
lvr2::DenseVertexMap< lvr2::VertexHandle > predecessors
predecessors while wave propagation
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.
WaveFrontPlannerConfig config
the current dynamic reconfigure planner configuration
lvr2::DenseVertexMap< float > potential
potential field / scalar distance field to the seed
void reconfigureCallback(wave_front_planner::WaveFrontPlannerConfig &cfg, uint32_t level)
Dynamic reconfigure callback.
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
stores the current vector map containing vectors pointing to the seed
std::string map_frame
the map coordinate frame / system id
lvr2::DenseVertexMap< lvr2::FaceHandle > cutting_faces
the face which is cut by the computed line to the source
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.
bool waveFrontUpdateWithS(lvr2::DenseVertexMap< float > &distances, const lvr2::DenseEdgeMap< float > &edge_weights, const lvr2::VertexHandle &v1, const lvr2::VertexHandle &v2, const lvr2::VertexHandle &v3)
void computeVectorMap()
Computes the vector field in a post processing. It rotates the predecessor edges by the stored angles...
std::string name
the user defined plugin name
lvr2::DenseVertexMap< float > direction
theta angles to the source of the wave front propagation
float goal_dist_offset
an offset that determines how far beyond the goal (robot's position) is propagated.
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.
bool publish_face_vectors
whether to also publish direction vectors at the triangle centers
bool publish_vector_field
whether to publish the vector field or not
bool waveFrontUpdate(lvr2::DenseVertexMap< float > &distances, const lvr2::DenseEdgeMap< float > &edge_weights, const lvr2::VertexHandle &v1, const lvr2::VertexHandle &v2, const lvr2::VertexHandle &v3)
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
ros::Publisher path_pub
publisher for the backtracked path
boost::shared_ptr< wave_front_planner::WaveFrontPlanner > Ptr
virtual ~WaveFrontPlanner()
Destructor.
boost::shared_ptr< dynamic_reconfigure::Server< wave_front_planner::WaveFrontPlannerConfig > > reconfigure_server_ptr
shared pointer to dynamic reconfigure server
mesh_map::MeshMap::Ptr mesh_map
shared pointer to the mesh map