moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
ompl_interface::ConstraintsLibrary Class Reference

#include <constraints_library.h>

Public Member Functions

 ConstraintsLibrary (ModelBasedPlanningContext *pcontext)
 
void loadConstraintApproximations (const std::string &path)
 
void saveConstraintApproximations (const std::string &path)
 
ConstraintApproximationConstructionResults addConstraintApproximation (const moveit_msgs::msg::Constraints &constr_sampling, const moveit_msgs::msg::Constraints &constr_hard, const std::string &group, const planning_scene::PlanningSceneConstPtr &scene, const ConstraintApproximationConstructionOptions &options)
 
ConstraintApproximationConstructionResults addConstraintApproximation (const moveit_msgs::msg::Constraints &constr, const std::string &group, const planning_scene::PlanningSceneConstPtr &scene, const ConstraintApproximationConstructionOptions &options)
 
void printConstraintApproximations (std::ostream &out=std::cout) const
 
void clearConstraintApproximations ()
 
void registerConstraintApproximation (const ConstraintApproximationPtr &approx)
 
const ConstraintApproximationPtr & getConstraintApproximation (const moveit_msgs::msg::Constraints &msg) const
 

Detailed Description

Definition at line 161 of file constraints_library.h.

Constructor & Destructor Documentation

◆ ConstraintsLibrary()

ompl_interface::ConstraintsLibrary::ConstraintsLibrary ( ModelBasedPlanningContext pcontext)
inline

Definition at line 164 of file constraints_library.h.

Member Function Documentation

◆ addConstraintApproximation() [1/2]

ConstraintApproximationConstructionResults ompl_interface::ConstraintsLibrary::addConstraintApproximation ( const moveit_msgs::msg::Constraints &  constr,
const std::string &  group,
const planning_scene::PlanningSceneConstPtr &  scene,
const ConstraintApproximationConstructionOptions options 
)

Definition at line 415 of file constraints_library.cpp.

Here is the call graph for this function:

◆ addConstraintApproximation() [2/2]

ConstraintApproximationConstructionResults ompl_interface::ConstraintsLibrary::addConstraintApproximation ( const moveit_msgs::msg::Constraints &  constr_sampling,
const moveit_msgs::msg::Constraints &  constr_hard,
const std::string &  group,
const planning_scene::PlanningSceneConstPtr &  scene,
const ConstraintApproximationConstructionOptions options 
)

Definition at line 422 of file constraints_library.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ clearConstraintApproximations()

void ompl_interface::ConstraintsLibrary::clearConstraintApproximations ( )

Definition at line 383 of file constraints_library.cpp.

◆ getConstraintApproximation()

const ConstraintApproximationPtr & ompl_interface::ConstraintsLibrary::getConstraintApproximation ( const moveit_msgs::msg::Constraints &  msg) const

Definition at line 404 of file constraints_library.cpp.

◆ loadConstraintApproximations()

void ompl_interface::ConstraintsLibrary::loadConstraintApproximations ( const std::string &  path)

Definition at line 277 of file constraints_library.cpp.

Here is the call graph for this function:

◆ printConstraintApproximations()

void ompl_interface::ConstraintsLibrary::printConstraintApproximations ( std::ostream &  out = std::cout) const

Definition at line 388 of file constraints_library.cpp.

◆ registerConstraintApproximation()

void ompl_interface::ConstraintsLibrary::registerConstraintApproximation ( const ConstraintApproximationPtr &  approx)
inline

Definition at line 186 of file constraints_library.h.

◆ saveConstraintApproximations()

void ompl_interface::ConstraintsLibrary::saveConstraintApproximations ( const std::string &  path)

Definition at line 346 of file constraints_library.cpp.

Here is the call graph for this function:

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