Public Member Functions | Private Attributes | List of all members
chomp_interface::CHOMPPlanningContext Class Reference

#include <chomp_planning_context.h>

Inheritance diagram for chomp_interface::CHOMPPlanningContext:
Inheritance graph
[legend]

Public Member Functions

 CHOMPPlanningContext (const std::string &name, const std::string &group, const moveit::core::RobotModelConstPtr &model, ros::NodeHandle &nh)
 
void clear () override
 
void initialize ()
 
bool solve (planning_interface::MotionPlanDetailedResponse &res) override
 
bool solve (planning_interface::MotionPlanResponse &res) override
 
bool terminate () override
 
 ~CHOMPPlanningContext () override=default
 
- 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 ()
 

Private Attributes

CHOMPInterfacePtr chomp_interface_
 
moveit::core::RobotModelConstPtr robot_model_
 

Additional Inherited Members

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

Detailed Description

Definition at line 78 of file chomp_planning_context.h.

Constructor & Destructor Documentation

◆ CHOMPPlanningContext()

chomp_interface::CHOMPPlanningContext::CHOMPPlanningContext ( const std::string &  name,
const std::string &  group,
const moveit::core::RobotModelConstPtr &  model,
ros::NodeHandle nh 
)

Definition at line 76 of file chomp_planning_context.cpp.

◆ ~CHOMPPlanningContext()

chomp_interface::CHOMPPlanningContext::~CHOMPPlanningContext ( )
overridedefault

Member Function Documentation

◆ clear()

void chomp_interface::CHOMPPlanningContext::clear ( )
overridevirtual

Implements planning_interface::PlanningContext.

Definition at line 110 of file chomp_planning_context.cpp.

◆ initialize()

void chomp_interface::CHOMPPlanningContext::initialize ( )

◆ solve() [1/2]

bool chomp_interface::CHOMPPlanningContext::solve ( planning_interface::MotionPlanDetailedResponse res)
overridevirtual

Implements planning_interface::PlanningContext.

Definition at line 83 of file chomp_planning_context.cpp.

◆ solve() [2/2]

bool chomp_interface::CHOMPPlanningContext::solve ( planning_interface::MotionPlanResponse res)
overridevirtual

Implements planning_interface::PlanningContext.

Definition at line 88 of file chomp_planning_context.cpp.

◆ terminate()

bool chomp_interface::CHOMPPlanningContext::terminate ( )
overridevirtual

Implements planning_interface::PlanningContext.

Definition at line 104 of file chomp_planning_context.cpp.

Member Data Documentation

◆ chomp_interface_

CHOMPInterfacePtr chomp_interface::CHOMPPlanningContext::chomp_interface_
private

Definition at line 95 of file chomp_planning_context.h.

◆ robot_model_

moveit::core::RobotModelConstPtr chomp_interface::CHOMPPlanningContext::robot_model_
private

Definition at line 96 of file chomp_planning_context.h.


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


chomp_interface
Author(s): Gil Jones
autogenerated on Sat May 3 2025 02:27:34