#include <dijkstra_mesh_planner.h>
Definition at line 49 of file dijkstra_mesh_planner.h.
◆ Ptr
◆ DijkstraMeshPlanner()
| dijkstra_mesh_planner::DijkstraMeshPlanner::DijkstraMeshPlanner |
( |
| ) |
|
◆ ~DijkstraMeshPlanner()
| dijkstra_mesh_planner::DijkstraMeshPlanner::~DijkstraMeshPlanner |
( |
| ) |
|
|
virtual |
◆ cancel()
| bool dijkstra_mesh_planner::DijkstraMeshPlanner::cancel |
( |
| ) |
|
|
virtual |
◆ 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]
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]
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()
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()
initializes this planner with the given plugin name and map
- Parameters
-
| name | name of this plugin |
| mesh_map_ptr | environment 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
-
| start | The start pose |
| goal | The goal pose |
| tolerance | If the goal is obstructed, how many meters the planner can relax the constraint in x and y before failing |
| plan | The plan... filled by the planner |
| cost | The cost for the the plan |
| message | Optional 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
-
| cfg | new configuration |
| level | level |
Definition at line 159 of file dijkstra_mesh_planner.cpp.
◆ cancel_planning
| std::atomic_bool dijkstra_mesh_planner::DijkstraMeshPlanner::cancel_planning |
|
private |
◆ config
| DijkstraMeshPlannerConfig dijkstra_mesh_planner::DijkstraMeshPlanner::config |
|
private |
◆ config_callback
| dynamic_reconfigure::Server<dijkstra_mesh_planner::DijkstraMeshPlannerConfig>::CallbackType dijkstra_mesh_planner::DijkstraMeshPlanner::config_callback |
|
private |
◆ cutting_faces
◆ first_config
| bool dijkstra_mesh_planner::DijkstraMeshPlanner::first_config |
|
private |
◆ goal_dist_offset
| float dijkstra_mesh_planner::DijkstraMeshPlanner::goal_dist_offset |
|
private |
◆ map_frame
| std::string dijkstra_mesh_planner::DijkstraMeshPlanner::map_frame |
|
private |
◆ mesh_map
◆ name
| std::string dijkstra_mesh_planner::DijkstraMeshPlanner::name |
|
private |
◆ path_pub
◆ potential
◆ predecessors
◆ private_nh
◆ publish_face_vectors
| bool dijkstra_mesh_planner::DijkstraMeshPlanner::publish_face_vectors |
|
private |
◆ publish_vector_field
| bool dijkstra_mesh_planner::DijkstraMeshPlanner::publish_vector_field |
|
private |
◆ reconfigure_server_ptr
| boost::shared_ptr<dynamic_reconfigure::Server<dijkstra_mesh_planner::DijkstraMeshPlannerConfig> > dijkstra_mesh_planner::DijkstraMeshPlanner::reconfigure_server_ptr |
|
private |
◆ vector_map
The documentation for this class was generated from the following files: