| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
#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 | 
Definition at line 161 of file constraints_library.h.
      
  | 
  inline | 
Definition at line 164 of file constraints_library.h.
| ompl_interface::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 431 of file constraints_library.cpp.
| ompl_interface::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 440 of file constraints_library.cpp.
| void ompl_interface::ConstraintsLibrary::clearConstraintApproximations | ( | ) | 
Definition at line 399 of file constraints_library.cpp.
| const ompl_interface::ConstraintApproximationPtr & ompl_interface::ConstraintsLibrary::getConstraintApproximation | ( | const moveit_msgs::msg::Constraints & | msg | ) | const | 
Definition at line 420 of file constraints_library.cpp.
| void ompl_interface::ConstraintsLibrary::loadConstraintApproximations | ( | const std::string & | path | ) | 
| void ompl_interface::ConstraintsLibrary::printConstraintApproximations | ( | std::ostream & | out = std::cout | ) | const | 
Definition at line 404 of file constraints_library.cpp.
      
  | 
  inline | 
Definition at line 186 of file constraints_library.h.
| void ompl_interface::ConstraintsLibrary::saveConstraintApproximations | ( | const std::string & | path | ) | 
Definition at line 366 of file constraints_library.cpp.