cb_base_navigation
Public Member Functions | Private Member Functions | Private Attributes | List of all members
cb_global_planner::AStarPlannerGPP Class Reference

#include <a_star_planner_gpp.h>

Inheritance diagram for cb_global_planner::AStarPlannerGPP:
Inheritance graph
[legend]

Public Member Functions

 AStarPlannerGPP ()
 Constructor for the AStarPlannerGPP object. More...
 
bool checkPlan (const std::vector< geometry_msgs::PoseStamped > &plan)
 Check if plan is valid. More...
 
void initialize (std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap_ros)
 Initialization function for the AStarPlannerGPP object. More...
 
bool 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)
 Given a set of goal constraints, compute a plan. More...
 
 ~AStarPlannerGPP ()
 
- Public Member Functions inherited from cb_global_planner::GlobalPlannerPlugin
virtual ~GlobalPlannerPlugin ()
 Virtual destructor for the interface. More...
 

Private Member Functions

bool calculateMapConstraintArea (std::vector< unsigned int > &mx, std::vector< unsigned int > &my, std::vector< tf2::Vector3 > &goal_positions)
 
bool constraintChanged (const cb_base_navigation_msgs::PositionConstraint &pc)
 
bool evaluateConstraint (const tf2::Vector3 &p)
 
void planToWorld (const std::vector< int > &plan_xs, const std::vector< int > &plan_ys, std::vector< geometry_msgs::PoseStamped > &plan)
 
bool queryEntityPose (const std::string &id, tf2::Transform &pose)
 
bool updateConstraintPositionsInConstraintFrame (const cb_base_navigation_msgs::PositionConstraint &pc)
 

Private Attributes

ros::ServiceClient ed_client_
 World model client. More...
 
costmap_2d::Costmap2DROSglobal_costmap_ros_
 
std::vector< tf2::Vector3 > goal_positions_in_constraint_frame_
 
bool initialized_
 
cb_base_navigation_msgs::PositionConstraint pc_
 
std::unique_ptr< AStarPlannerplanner_
 
tf2_ros::Buffer * tf_
 

Additional Inherited Members

- Protected Member Functions inherited from cb_global_planner::GlobalPlannerPlugin
 GlobalPlannerPlugin ()
 

Detailed Description

Definition at line 41 of file a_star_planner_gpp.h.

Constructor & Destructor Documentation

◆ AStarPlannerGPP()

cb_global_planner::AStarPlannerGPP::AStarPlannerGPP ( )

Constructor for the AStarPlannerGPP object.

Definition at line 53 of file a_star_planner_gpp.cpp.

◆ ~AStarPlannerGPP()

cb_global_planner::AStarPlannerGPP::~AStarPlannerGPP ( )

Definition at line 73 of file a_star_planner_gpp.cpp.

Member Function Documentation

◆ calculateMapConstraintArea()

bool cb_global_planner::AStarPlannerGPP::calculateMapConstraintArea ( std::vector< unsigned int > &  mx,
std::vector< unsigned int > &  my,
std::vector< tf2::Vector3 > &  goal_positions 
)
private

Definition at line 240 of file a_star_planner_gpp.cpp.

◆ checkPlan()

bool cb_global_planner::AStarPlannerGPP::checkPlan ( const std::vector< geometry_msgs::PoseStamped > &  plan)
virtual

Check if plan is valid.

Parameters
planplan to check
Returns
Validity of the plan

Implements cb_global_planner::GlobalPlannerPlugin.

Definition at line 311 of file a_star_planner_gpp.cpp.

◆ constraintChanged()

bool cb_global_planner::AStarPlannerGPP::constraintChanged ( const cb_base_navigation_msgs::PositionConstraint &  pc)
inlineprivate

Definition at line 84 of file a_star_planner_gpp.h.

◆ evaluateConstraint()

bool cb_global_planner::AStarPlannerGPP::evaluateConstraint ( const tf2::Vector3 &  p)
private

◆ initialize()

void cb_global_planner::AStarPlannerGPP::initialize ( std::string  name,
tf2_ros::Buffer *  tf,
costmap_2d::Costmap2DROS global_costmap_ros 
)
virtual

Initialization function for the AStarPlannerGPP object.

Parameters
nameThe name of this planner
tfPointer to the tf2_ros::Buffer
costmap_rosA pointer to the ROS wrapper of the costmap to use for planning

Implements cb_global_planner::GlobalPlannerPlugin.

Definition at line 57 of file a_star_planner_gpp.cpp.

◆ 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
startThe start pose
pcPosition contraints on the goal position
planThe 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

Definition at line 278 of file a_star_planner_gpp.cpp.

◆ queryEntityPose()

bool cb_global_planner::AStarPlannerGPP::queryEntityPose ( const std::string id,
tf2::Transform &  pose 
)
private

Definition at line 20 of file a_star_planner_gpp.cpp.

◆ updateConstraintPositionsInConstraintFrame()

bool cb_global_planner::AStarPlannerGPP::updateConstraintPositionsInConstraintFrame ( const cb_base_navigation_msgs::PositionConstraint &  pc)
private

Definition at line 194 of file a_star_planner_gpp.cpp.

Member Data Documentation

◆ ed_client_

ros::ServiceClient cb_global_planner::AStarPlannerGPP::ed_client_
private

World model client.

Definition at line 95 of file a_star_planner_gpp.h.

◆ global_costmap_ros_

costmap_2d::Costmap2DROS* cb_global_planner::AStarPlannerGPP::global_costmap_ros_
private

Definition at line 79 of file a_star_planner_gpp.h.

◆ goal_positions_in_constraint_frame_

std::vector<tf2::Vector3> cb_global_planner::AStarPlannerGPP::goal_positions_in_constraint_frame_
private

Definition at line 92 of file a_star_planner_gpp.h.

◆ initialized_

bool cb_global_planner::AStarPlannerGPP::initialized_
private

Definition at line 82 of file a_star_planner_gpp.h.

◆ pc_

cb_base_navigation_msgs::PositionConstraint cb_global_planner::AStarPlannerGPP::pc_
private

Definition at line 91 of file a_star_planner_gpp.h.

◆ planner_

std::unique_ptr<AStarPlanner> cb_global_planner::AStarPlannerGPP::planner_
private

Definition at line 80 of file a_star_planner_gpp.h.

◆ tf_

tf2_ros::Buffer* cb_global_planner::AStarPlannerGPP::tf_
private

Definition at line 81 of file a_star_planner_gpp.h.


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