#include <a_star_planner_gpp.h>
Definition at line 41 of file a_star_planner_gpp.h.
◆ AStarPlannerGPP()
cb_global_planner::AStarPlannerGPP::AStarPlannerGPP |
( |
| ) |
|
◆ ~AStarPlannerGPP()
cb_global_planner::AStarPlannerGPP::~AStarPlannerGPP |
( |
| ) |
|
◆ calculateMapConstraintArea()
bool cb_global_planner::AStarPlannerGPP::calculateMapConstraintArea |
( |
std::vector< unsigned int > & |
mx, |
|
|
std::vector< unsigned int > & |
my, |
|
|
std::vector< tf2::Vector3 > & |
goal_positions |
|
) |
| |
|
private |
◆ checkPlan()
bool cb_global_planner::AStarPlannerGPP::checkPlan |
( |
const std::vector< geometry_msgs::PoseStamped > & |
plan | ) |
|
|
virtual |
◆ constraintChanged()
bool cb_global_planner::AStarPlannerGPP::constraintChanged |
( |
const cb_base_navigation_msgs::PositionConstraint & |
pc | ) |
|
|
inlineprivate |
◆ evaluateConstraint()
bool cb_global_planner::AStarPlannerGPP::evaluateConstraint |
( |
const tf2::Vector3 & |
p | ) |
|
|
private |
◆ initialize()
◆ makePlan()
bool cb_global_planner::AStarPlannerGPP::makePlan |
( |
const geometry_msgs::PoseStamped & |
start, |
|
|
const cb_base_navigation_msgs::PositionConstraint & |
pc, |
|
|
std::vector< geometry_msgs::PoseStamped > & |
plan, |
|
|
std::vector< tf2::Vector3 > & |
goal_positions |
|
) |
| |
|
virtual |
Given a set of goal constraints, compute a plan.
- Parameters
-
start | The start pose |
pc | Position contraints on the goal position |
plan | The plan... filled by the planner |
- Returns
- True if a valid plan was found, false otherwise
Implements cb_global_planner::GlobalPlannerPlugin.
Definition at line 77 of file a_star_planner_gpp.cpp.
◆ planToWorld()
void cb_global_planner::AStarPlannerGPP::planToWorld |
( |
const std::vector< int > & |
plan_xs, |
|
|
const std::vector< int > & |
plan_ys, |
|
|
std::vector< geometry_msgs::PoseStamped > & |
plan |
|
) |
| |
|
private |
◆ queryEntityPose()
bool cb_global_planner::AStarPlannerGPP::queryEntityPose |
( |
const std::string & |
id, |
|
|
tf2::Transform & |
pose |
|
) |
| |
|
private |
◆ updateConstraintPositionsInConstraintFrame()
bool cb_global_planner::AStarPlannerGPP::updateConstraintPositionsInConstraintFrame |
( |
const cb_base_navigation_msgs::PositionConstraint & |
pc | ) |
|
|
private |
◆ ed_client_
ros::ServiceClient cb_global_planner::AStarPlannerGPP::ed_client_ |
|
private |
◆ global_costmap_ros_
◆ goal_positions_in_constraint_frame_
std::vector<tf2::Vector3> cb_global_planner::AStarPlannerGPP::goal_positions_in_constraint_frame_ |
|
private |
◆ initialized_
bool cb_global_planner::AStarPlannerGPP::initialized_ |
|
private |
◆ pc_
cb_base_navigation_msgs::PositionConstraint cb_global_planner::AStarPlannerGPP::pc_ |
|
private |
◆ planner_
◆ tf_
tf2_ros::Buffer* cb_global_planner::AStarPlannerGPP::tf_ |
|
private |
The documentation for this class was generated from the following files: