Public Member Functions | Private Attributes | List of all members
base_local_planner::LocalPlannerUtil Class Reference

Helper class implementing infrastructure code many local planner implementations may need. More...

#include <local_planner_util.h>

Public Member Functions

costmap_2d::Costmap2DgetCostmap ()
 
LocalPlannerLimits getCurrentLimits ()
 
std::string getGlobalFrame ()
 
bool getGoal (geometry_msgs::PoseStamped &goal_pose)
 
bool getLocalPlan (const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
 
void initialize (tf2_ros::Buffer *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
 
 LocalPlannerUtil ()
 
void reconfigureCB (LocalPlannerLimits &config, bool restore_defaults)
 Callback to update the local planner's parameters. More...
 
bool setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
 
 ~LocalPlannerUtil ()
 

Private Attributes

costmap_2d::Costmap2Dcostmap_
 
LocalPlannerLimits default_limits_
 
std::string global_frame_
 
std::vector< geometry_msgs::PoseStamped > global_plan_
 
bool initialized_
 
LocalPlannerLimits limits_
 
boost::mutex limits_configuration_mutex_
 
std::string name_
 
bool setup_
 
tf2_ros::Buffertf_
 

Detailed Description

Helper class implementing infrastructure code many local planner implementations may need.

Definition at line 92 of file local_planner_util.h.

Constructor & Destructor Documentation

◆ LocalPlannerUtil()

base_local_planner::LocalPlannerUtil::LocalPlannerUtil ( )
inline

Definition at line 119 of file local_planner_util.h.

◆ ~LocalPlannerUtil()

base_local_planner::LocalPlannerUtil::~LocalPlannerUtil ( )
inline

Definition at line 121 of file local_planner_util.h.

Member Function Documentation

◆ getCostmap()

costmap_2d::Costmap2D * base_local_planner::LocalPlannerUtil::getCostmap ( )

Definition at line 108 of file local_planner_util.cpp.

◆ getCurrentLimits()

LocalPlannerLimits base_local_planner::LocalPlannerUtil::getCurrentLimits ( )

Definition at line 112 of file local_planner_util.cpp.

◆ getGlobalFrame()

std::string base_local_planner::LocalPlannerUtil::getGlobalFrame ( )
inline

Definition at line 138 of file local_planner_util.h.

◆ getGoal()

bool base_local_planner::LocalPlannerUtil::getGoal ( geometry_msgs::PoseStamped &  goal_pose)

Definition at line 118 of file local_planner_util.cpp.

◆ getLocalPlan()

bool base_local_planner::LocalPlannerUtil::getLocalPlan ( const geometry_msgs::PoseStamped &  global_pose,
std::vector< geometry_msgs::PoseStamped > &  transformed_plan 
)

Definition at line 140 of file local_planner_util.cpp.

◆ initialize()

void base_local_planner::LocalPlannerUtil::initialize ( tf2_ros::Buffer tf,
costmap_2d::Costmap2D costmap,
std::string  global_frame 
)

Definition at line 79 of file local_planner_util.cpp.

◆ reconfigureCB()

void base_local_planner::LocalPlannerUtil::reconfigureCB ( LocalPlannerLimits config,
bool  restore_defaults 
)

Callback to update the local planner's parameters.

Definition at line 94 of file local_planner_util.cpp.

◆ setPlan()

bool base_local_planner::LocalPlannerUtil::setPlan ( const std::vector< geometry_msgs::PoseStamped > &  orig_global_plan)

Definition at line 126 of file local_planner_util.cpp.

Member Data Documentation

◆ costmap_

costmap_2d::Costmap2D* base_local_planner::LocalPlannerUtil::costmap_
private

Definition at line 99 of file local_planner_util.h.

◆ default_limits_

LocalPlannerLimits base_local_planner::LocalPlannerUtil::default_limits_
private

Definition at line 108 of file local_planner_util.h.

◆ global_frame_

std::string base_local_planner::LocalPlannerUtil::global_frame_
private

Definition at line 97 of file local_planner_util.h.

◆ global_plan_

std::vector<geometry_msgs::PoseStamped> base_local_planner::LocalPlannerUtil::global_plan_
private

Definition at line 103 of file local_planner_util.h.

◆ initialized_

bool base_local_planner::LocalPlannerUtil::initialized_
private

Definition at line 110 of file local_planner_util.h.

◆ limits_

LocalPlannerLimits base_local_planner::LocalPlannerUtil::limits_
private

Definition at line 109 of file local_planner_util.h.

◆ limits_configuration_mutex_

boost::mutex base_local_planner::LocalPlannerUtil::limits_configuration_mutex_
private

Definition at line 106 of file local_planner_util.h.

◆ name_

std::string base_local_planner::LocalPlannerUtil::name_
private

Definition at line 96 of file local_planner_util.h.

◆ setup_

bool base_local_planner::LocalPlannerUtil::setup_
private

Definition at line 107 of file local_planner_util.h.

◆ tf_

tf2_ros::Buffer* base_local_planner::LocalPlannerUtil::tf_
private

Definition at line 100 of file local_planner_util.h.


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


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24