Public Member Functions | Static Public Attributes | Private Attributes | List of all members
default_planner_request_adapters::FixWorkspaceBounds Class Reference
Inheritance diagram for default_planner_request_adapters::FixWorkspaceBounds:
Inheritance graph
[legend]

Public Member Functions

virtual bool adaptAndPlan (const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const
 
 FixWorkspaceBounds ()
 
virtual std::string getDescription () const
 
- Public Member Functions inherited from planning_request_adapter::PlanningRequestAdapter
bool adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
 
bool adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const
 
 PlanningRequestAdapter ()
 
virtual ~PlanningRequestAdapter ()
 

Static Public Attributes

static const std::string WBOUNDS_PARAM_NAME = "default_workspace_bounds"
 

Private Attributes

ros::NodeHandle nh_
 
double workspace_extent_
 

Additional Inherited Members

- Public Types inherited from planning_request_adapter::PlanningRequestAdapter
typedef boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
 

Detailed Description

Definition at line 43 of file fix_workspace_bounds.cpp.

Constructor & Destructor Documentation

default_planner_request_adapters::FixWorkspaceBounds::FixWorkspaceBounds ( )
inline

Definition at line 48 of file fix_workspace_bounds.cpp.

Member Function Documentation

virtual bool default_planner_request_adapters::FixWorkspaceBounds::adaptAndPlan ( const PlannerFn planner,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res,
std::vector< std::size_t > &  added_path_index 
) const
inlinevirtual
virtual std::string default_planner_request_adapters::FixWorkspaceBounds::getDescription ( ) const
inlinevirtual

Reimplemented from planning_request_adapter::PlanningRequestAdapter.

Definition at line 60 of file fix_workspace_bounds.cpp.

Member Data Documentation

ros::NodeHandle default_planner_request_adapters::FixWorkspaceBounds::nh_
private

Definition at line 88 of file fix_workspace_bounds.cpp.

const std::string default_planner_request_adapters::FixWorkspaceBounds::WBOUNDS_PARAM_NAME = "default_workspace_bounds"
static

Definition at line 46 of file fix_workspace_bounds.cpp.

double default_planner_request_adapters::FixWorkspaceBounds::workspace_extent_
private

Definition at line 89 of file fix_workspace_bounds.cpp.


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


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:17:34