Go to the documentation of this file.
38 #ifndef MESH_NAVIGATION__dijkstra_mesh_planner_H
39 #define MESH_NAVIGATION__DIJKSTRA_MESH_PLANNER_H
42 #include <mbf_msgs/GetPathResult.h>
44 #include <dijkstra_mesh_planner/DijkstraMeshPlannerConfig.h>
45 #include <nav_msgs/Path.h>
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);
160 void reconfigureCallback(dijkstra_mesh_planner::DijkstraMeshPlannerConfig& cfg, uint32_t level);
184 dynamic_reconfigure::Server<dijkstra_mesh_planner::DijkstraMeshPlannerConfig>::CallbackType
config_callback;
201 #endif // MESH_NAVIGATION__DIJKSTRA_MESH_PLANNER_H
mesh_map::MeshMap::Ptr mesh_map
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
lvr2::DenseVertexMap< lvr2::VertexHandle > predecessors
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...
bool publish_face_vectors
lvr2::DenseVertexMap< lvr2::FaceHandle > cutting_faces
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
lvr2::DenseVertexMap< mesh_map::Vector > getVectorMap()
delivers vector field which has been generated during the latest planning
void computeVectorMap()
calculates the vector field based on the current predecessors map and stores it to the vector_map fie...
virtual ~DijkstraMeshPlanner()
Destructor.
bool publish_vector_field
void reconfigureCallback(dijkstra_mesh_planner::DijkstraMeshPlannerConfig &cfg, uint32_t level)
gets called on new incoming reconfigure parameters
std::atomic_bool cancel_planning
boost::shared_ptr< dynamic_reconfigure::Server< dijkstra_mesh_planner::DijkstraMeshPlannerConfig > > reconfigure_server_ptr
lvr2::DenseVertexMap< float > potential
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
DijkstraMeshPlannerConfig config
dynamic_reconfigure::Server< dijkstra_mesh_planner::DijkstraMeshPlannerConfig >::CallbackType config_callback
ros::NodeHandle private_nh
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.
boost::shared_ptr< dijkstra_mesh_planner::DijkstraMeshPlanner > Ptr