Public Member Functions | Public Attributes | Protected Attributes | List of all members
pilz::PlanningContextBase< GeneratorT > Class Template Reference

PlanningContext for obtaining trajectories. More...

#include <planning_context_base.h>

Inheritance diagram for pilz::PlanningContextBase< GeneratorT >:
Inheritance graph
[legend]

Public Member Functions

virtual void clear () override
 
 PlanningContextBase (const std::string &name, const std::string &group, const moveit::core::RobotModelConstPtr &model, const pilz::LimitsContainer &limits)
 
virtual bool solve (planning_interface::MotionPlanResponse &res) override
 Calculates a trajectory for the request this context is currently set for. More...
 
virtual bool solve (planning_interface::MotionPlanDetailedResponse &res) override
 Will return the same trajectory as solve(planning_interface::MotionPlanResponse& res) This function just delegates to the common response however here the same trajectory is stored with the descriptions "plan", "simplify", "interpolate". More...
 
virtual bool terminate () override
 Will terminate solve() More...
 
virtual ~PlanningContextBase ()
 
- Public Member Functions inherited from planning_interface::PlanningContext
const std::string & getGroupName () const
 
const MotionPlanRequestgetMotionPlanRequest () const
 
const std::string & getName () const
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene () const
 
 PlanningContext (const std::string &name, const std::string &group)
 
void setMotionPlanRequest (const MotionPlanRequest &request)
 
void setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene)
 
virtual ~PlanningContext ()
 

Public Attributes

pilz::LimitsContainer limits_
 Joint limits to be used during planning. More...
 
robot_model::RobotModelConstPtr model_
 The robot model. More...
 
std::atomic_bool terminated_
 Flag if terminated. More...
 

Protected Attributes

GeneratorT generator_
 
- Protected Attributes inherited from planning_interface::PlanningContext
std::string group_
 
std::string name_
 
planning_scene::PlanningSceneConstPtr planning_scene_
 
MotionPlanRequest request_
 

Detailed Description

template<typename GeneratorT>
class pilz::PlanningContextBase< GeneratorT >

PlanningContext for obtaining trajectories.

Definition at line 40 of file planning_context_base.h.

Constructor & Destructor Documentation

template<typename GeneratorT>
pilz::PlanningContextBase< GeneratorT >::PlanningContextBase ( const std::string &  name,
const std::string &  group,
const moveit::core::RobotModelConstPtr &  model,
const pilz::LimitsContainer limits 
)
inline

Definition at line 44 of file planning_context_base.h.

template<typename GeneratorT>
virtual pilz::PlanningContextBase< GeneratorT >::~PlanningContextBase ( )
inlinevirtual

Definition at line 54 of file planning_context_base.h.

Member Function Documentation

template<typename GeneratorT >
void pilz::PlanningContextBase< GeneratorT >::clear ( void  )
overridevirtual

Implements planning_interface::PlanningContext.

Definition at line 157 of file planning_context_base.h.

template<typename GeneratorT >
bool pilz::PlanningContextBase< GeneratorT >::solve ( planning_interface::MotionPlanResponse res)
overridevirtual

Calculates a trajectory for the request this context is currently set for.

Parameters
resThe result containing the respective trajectory, or error_code on failure
Returns
true on success, false otherwise

Implements planning_interface::PlanningContext.

Definition at line 100 of file planning_context_base.h.

template<typename GeneratorT >
bool pilz::PlanningContextBase< GeneratorT >::solve ( planning_interface::MotionPlanDetailedResponse res)
overridevirtual

Will return the same trajectory as solve(planning_interface::MotionPlanResponse& res) This function just delegates to the common response however here the same trajectory is stored with the descriptions "plan", "simplify", "interpolate".

Parameters
resThe detailed response
Returns
true on success, false otherwise

Implements planning_interface::PlanningContext.

Definition at line 124 of file planning_context_base.h.

template<typename GeneratorT >
bool pilz::PlanningContextBase< GeneratorT >::terminate ( )
overridevirtual

Will terminate solve()

Returns
Note
Currently will not stop a runnning solve but

Implements planning_interface::PlanningContext.

Definition at line 148 of file planning_context_base.h.

Member Data Documentation

template<typename GeneratorT>
GeneratorT pilz::PlanningContextBase< GeneratorT >::generator_
protected

Definition at line 94 of file planning_context_base.h.

template<typename GeneratorT>
pilz::LimitsContainer pilz::PlanningContextBase< GeneratorT >::limits_

Joint limits to be used during planning.

Definition at line 91 of file planning_context_base.h.

template<typename GeneratorT>
robot_model::RobotModelConstPtr pilz::PlanningContextBase< GeneratorT >::model_

The robot model.

Definition at line 88 of file planning_context_base.h.

template<typename GeneratorT>
std::atomic_bool pilz::PlanningContextBase< GeneratorT >::terminated_

Flag if terminated.

Definition at line 85 of file planning_context_base.h.


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


pilz_trajectory_generation
Author(s):
autogenerated on Mon Apr 6 2020 03:17:33