Public Types | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
dijkstra_mesh_planner::DijkstraMeshPlanner Class Reference

#include <dijkstra_mesh_planner.h>

Inheritance diagram for dijkstra_mesh_planner::DijkstraMeshPlanner:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< dijkstra_mesh_planner::DijkstraMeshPlannerPtr
 
- Public Types inherited from mbf_mesh_core::MeshPlanner
typedef boost::shared_ptr< mbf_mesh_core::MeshPlannerPtr
 
- Public Types inherited from mbf_abstract_core::AbstractPlanner
typedef boost::shared_ptr< ::mbf_abstract_core::AbstractPlannerPtr
 

Public Member Functions

virtual bool cancel ()
 Requests the planner to cancel, e.g. if it takes too much time. More...
 
 DijkstraMeshPlanner ()
 
lvr2::DenseVertexMap< mesh_map::VectorgetVectorMap ()
 delivers vector field which has been generated during the latest planning More...
 
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 More...
 
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. More...
 
virtual ~DijkstraMeshPlanner ()
 Destructor. More...
 
- Public Member Functions inherited from mbf_mesh_core::MeshPlanner
virtual ~MeshPlanner ()
 
- Public Member Functions inherited from mbf_abstract_core::AbstractPlanner
virtual ~AbstractPlanner ()
 

Protected Member Functions

void computeVectorMap ()
 calculates the vector field based on the current predecessors map and stores it to the vector_map field of this class More...
 
uint32_t dijkstra (const mesh_map::Vector &start, const mesh_map::Vector &goal, const lvr2::DenseEdgeMap< float > &edge_weights, const lvr2::DenseVertexMap< float > &costs, std::list< lvr2::VertexHandle > &path, lvr2::DenseVertexMap< float > &distances, lvr2::DenseVertexMap< lvr2::VertexHandle > &predecessors)
 runs dijkstra path planning More...
 
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 potential and predecessors of this class More...
 
void reconfigureCallback (dijkstra_mesh_planner::DijkstraMeshPlannerConfig &cfg, uint32_t level)
 gets called on new incoming reconfigure parameters More...
 
- Protected Member Functions inherited from mbf_mesh_core::MeshPlanner
 MeshPlanner ()
 
- Protected Member Functions inherited from mbf_abstract_core::AbstractPlanner
 AbstractPlanner ()
 

Private Attributes

std::atomic_bool cancel_planning
 
DijkstraMeshPlannerConfig config
 
dynamic_reconfigure::Server< dijkstra_mesh_planner::DijkstraMeshPlannerConfig >::CallbackType config_callback
 
lvr2::DenseVertexMap< lvr2::FaceHandlecutting_faces
 
bool first_config
 
float goal_dist_offset
 
std::string map_frame
 
mesh_map::MeshMap::Ptr mesh_map
 
std::string name
 
ros::Publisher path_pub
 
lvr2::DenseVertexMap< float > potential
 
lvr2::DenseVertexMap< lvr2::VertexHandlepredecessors
 
ros::NodeHandle private_nh
 
bool publish_face_vectors
 
bool publish_vector_field
 
boost::shared_ptr< dynamic_reconfigure::Server< dijkstra_mesh_planner::DijkstraMeshPlannerConfig > > reconfigure_server_ptr
 
lvr2::DenseVertexMap< mesh_map::Vectorvector_map
 

Detailed Description

Definition at line 49 of file dijkstra_mesh_planner.h.

Member Typedef Documentation

◆ Ptr

Definition at line 52 of file dijkstra_mesh_planner.h.

Constructor & Destructor Documentation

◆ DijkstraMeshPlanner()

dijkstra_mesh_planner::DijkstraMeshPlanner::DijkstraMeshPlanner ( )

Definition at line 48 of file dijkstra_mesh_planner.cpp.

◆ ~DijkstraMeshPlanner()

dijkstra_mesh_planner::DijkstraMeshPlanner::~DijkstraMeshPlanner ( )
virtual

Destructor.

Definition at line 52 of file dijkstra_mesh_planner.cpp.

Member Function Documentation

◆ cancel()

bool dijkstra_mesh_planner::DijkstraMeshPlanner::cancel ( )
virtual

Requests the planner to cancel, e.g. if it takes too much time.

Returns
True if a cancel has been successfully requested, false if not implemented.

Implements mbf_mesh_core::MeshPlanner.

Definition at line 123 of file dijkstra_mesh_planner.cpp.

◆ computeVectorMap()

void dijkstra_mesh_planner::DijkstraMeshPlanner::computeVectorMap ( )
protected

calculates the vector field based on the current predecessors map and stores it to the vector_map field of this class

Definition at line 171 of file dijkstra_mesh_planner.cpp.

◆ dijkstra() [1/2]

uint32_t dijkstra_mesh_planner::DijkstraMeshPlanner::dijkstra ( const mesh_map::Vector start,
const mesh_map::Vector goal,
const lvr2::DenseEdgeMap< float > &  edge_weights,
const lvr2::DenseVertexMap< float > &  costs,
std::list< lvr2::VertexHandle > &  path,
lvr2::DenseVertexMap< float > &  distances,
lvr2::DenseVertexMap< lvr2::VertexHandle > &  predecessors 
)
protected

runs dijkstra path planning

Parameters
start[in]3D starting position of the requested path
goal[in]3D goal position of the requested path
edge_weights[in]edge distances of the map
costs[in]vertex costs of the map
path[out]optimal path from the given starting position to tie goal position
distances[out]per vertex distances to goal
predecessors[out]dense predecessor map for all visited vertices
Returns
result code in form of GetPath action result: SUCCESS, NO_PATH_FOUND, INVALID_START, INVALID_GOAL, and CANCELED are possible

Definition at line 199 of file dijkstra_mesh_planner.cpp.

◆ dijkstra() [2/2]

uint32_t dijkstra_mesh_planner::DijkstraMeshPlanner::dijkstra ( const mesh_map::Vector start,
const mesh_map::Vector goal,
std::list< lvr2::VertexHandle > &  path 
)
protected

runs dijkstra path planning and stores the resulting distances and predecessors to the fields potential and predecessors of this class

Parameters
start[in]3D starting position of the requested path
goal[in]3D goal position of the requested path
path[out]optimal path from the given starting position to tie goal position
Returns
result code in form of GetPath action result: SUCCESS, NO_PATH_FOUND, INVALID_START, INVALID_GOAL, and CANCELED are possible

Definition at line 193 of file dijkstra_mesh_planner.cpp.

◆ getVectorMap()

lvr2::DenseVertexMap< mesh_map::Vector > dijkstra_mesh_planner::DijkstraMeshPlanner::getVectorMap ( )

delivers vector field which has been generated during the latest planning

Returns
vector field of the plan

Definition at line 154 of file dijkstra_mesh_planner.cpp.

◆ initialize()

bool dijkstra_mesh_planner::DijkstraMeshPlanner::initialize ( const std::string &  name,
const boost::shared_ptr< mesh_map::MeshMap > &  mesh_map_ptr 
)
virtual

initializes this planner with the given plugin name and map

Parameters
namename of this plugin
mesh_map_ptrenvironment map on which planning is done
Returns
true if initialization was successul; else false

Implements mbf_mesh_core::MeshPlanner.

Definition at line 129 of file dijkstra_mesh_planner.cpp.

◆ makePlan()

uint32_t dijkstra_mesh_planner::DijkstraMeshPlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance,
std::vector< geometry_msgs::PoseStamped > &  plan,
double &  cost,
std::string &  message 
)
virtual

Given a goal pose in the world, compute a plan.

Parameters
startThe start pose
goalThe goal pose
toleranceIf the goal is obstructed, how many meters the planner can relax the constraint in x and y before failing
planThe plan... filled by the planner
costThe cost for the the plan
messageOptional more detailed outcome as a string
Returns
Result code as described on GetPath action result: SUCCESS = 0 1..9 are reserved as plugin specific non-error results FAILURE = 50 # Unspecified failure, only used for old, non-mfb_core based plugins CANCELED = 51 INVALID_START = 52 INVALID_GOAL = 53 NO_PATH_FOUND = 54 PAT_EXCEEDED = 55 EMPTY_PATH = 56 TF_ERROR = 57 NOT_INITIALIZED = 58 INVALID_PLUGIN = 59 INTERNAL_ERROR = 60 71..99 are reserved as plugin specific errors

Implements mbf_mesh_core::MeshPlanner.

Definition at line 56 of file dijkstra_mesh_planner.cpp.

◆ reconfigureCallback()

void dijkstra_mesh_planner::DijkstraMeshPlanner::reconfigureCallback ( dijkstra_mesh_planner::DijkstraMeshPlannerConfig &  cfg,
uint32_t  level 
)
protected

gets called on new incoming reconfigure parameters

Parameters
cfgnew configuration
levellevel

Definition at line 159 of file dijkstra_mesh_planner.cpp.

Member Data Documentation

◆ cancel_planning

std::atomic_bool dijkstra_mesh_planner::DijkstraMeshPlanner::cancel_planning
private

Definition at line 170 of file dijkstra_mesh_planner.h.

◆ config

DijkstraMeshPlannerConfig dijkstra_mesh_planner::DijkstraMeshPlanner::config
private

Definition at line 186 of file dijkstra_mesh_planner.h.

◆ config_callback

dynamic_reconfigure::Server<dijkstra_mesh_planner::DijkstraMeshPlannerConfig>::CallbackType dijkstra_mesh_planner::DijkstraMeshPlanner::config_callback
private

Definition at line 184 of file dijkstra_mesh_planner.h.

◆ cutting_faces

lvr2::DenseVertexMap<lvr2::FaceHandle> dijkstra_mesh_planner::DijkstraMeshPlanner::cutting_faces
private

Definition at line 191 of file dijkstra_mesh_planner.h.

◆ first_config

bool dijkstra_mesh_planner::DijkstraMeshPlanner::first_config
private

Definition at line 185 of file dijkstra_mesh_planner.h.

◆ goal_dist_offset

float dijkstra_mesh_planner::DijkstraMeshPlanner::goal_dist_offset
private

Definition at line 180 of file dijkstra_mesh_planner.h.

◆ map_frame

std::string dijkstra_mesh_planner::DijkstraMeshPlanner::map_frame
private

Definition at line 178 of file dijkstra_mesh_planner.h.

◆ mesh_map

mesh_map::MeshMap::Ptr dijkstra_mesh_planner::DijkstraMeshPlanner::mesh_map
private

Definition at line 164 of file dijkstra_mesh_planner.h.

◆ name

std::string dijkstra_mesh_planner::DijkstraMeshPlanner::name
private

Definition at line 166 of file dijkstra_mesh_planner.h.

◆ path_pub

ros::Publisher dijkstra_mesh_planner::DijkstraMeshPlanner::path_pub
private

Definition at line 172 of file dijkstra_mesh_planner.h.

◆ potential

lvr2::DenseVertexMap<float> dijkstra_mesh_planner::DijkstraMeshPlanner::potential
private

Definition at line 196 of file dijkstra_mesh_planner.h.

◆ predecessors

lvr2::DenseVertexMap<lvr2::VertexHandle> dijkstra_mesh_planner::DijkstraMeshPlanner::predecessors
private

Definition at line 189 of file dijkstra_mesh_planner.h.

◆ private_nh

ros::NodeHandle dijkstra_mesh_planner::DijkstraMeshPlanner::private_nh
private

Definition at line 168 of file dijkstra_mesh_planner.h.

◆ publish_face_vectors

bool dijkstra_mesh_planner::DijkstraMeshPlanner::publish_face_vectors
private

Definition at line 176 of file dijkstra_mesh_planner.h.

◆ publish_vector_field

bool dijkstra_mesh_planner::DijkstraMeshPlanner::publish_vector_field
private

Definition at line 174 of file dijkstra_mesh_planner.h.

◆ reconfigure_server_ptr

boost::shared_ptr<dynamic_reconfigure::Server<dijkstra_mesh_planner::DijkstraMeshPlannerConfig> > dijkstra_mesh_planner::DijkstraMeshPlanner::reconfigure_server_ptr
private

Definition at line 183 of file dijkstra_mesh_planner.h.

◆ vector_map

lvr2::DenseVertexMap<mesh_map::Vector> dijkstra_mesh_planner::DijkstraMeshPlanner::vector_map
private

Definition at line 194 of file dijkstra_mesh_planner.h.


The documentation for this class was generated from the following files:


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