$search
A ROS wrapper around a ompl::base::StateValidityChecker object. More...
#include <ompl_ros_state_validity_checker.h>
A ROS wrapper around a ompl::base::StateValidityChecker object.
Definition at line 56 of file ompl_ros_state_validity_checker.h.
ompl_ros_interface::OmplRosStateValidityChecker::OmplRosStateValidityChecker | ( | ompl::base::SpaceInformation * | si, | |
planning_environment::CollisionModelsInterface * | cmi | |||
) | [inline] |
A default constructor.
si | - A pointer to the space information used by this checker | |
planning_monitor | - A pointer to the planning monitor instance used by this checker |
Definition at line 64 of file ompl_ros_state_validity_checker.h.
void ompl_ros_interface::OmplRosStateValidityChecker::configureOnRequest | ( | planning_models::KinematicState * | kinematic_state, | |
planning_models::KinematicState::JointStateGroup * | physical_joint_state_group, | |||
const arm_navigation_msgs::GetMotionPlan::Request & | request | |||
) | [virtual] |
Reimplemented in ompl_ros_interface::OmplRosTaskSpaceValidityChecker.
Definition at line 41 of file ompl_ros_state_validity_checker.cpp.
arm_navigation_msgs::ArmNavigationErrorCodes ompl_ros_interface::OmplRosStateValidityChecker::getLastErrorCode | ( | ) | [inline] |
Definition at line 92 of file ompl_ros_state_validity_checker.h.
arm_navigation_msgs::Constraints ompl_ros_interface::OmplRosStateValidityChecker::getPhysicalConstraints | ( | const arm_navigation_msgs::Constraints & | constraints | ) | [protected] |
Definition at line 66 of file ompl_ros_state_validity_checker.cpp.
virtual bool ompl_ros_interface::OmplRosStateValidityChecker::isStateValid | ( | const ompl::base::State * | ompl_state | ) | [pure virtual] |
virtual bool ompl_ros_interface::OmplRosStateValidityChecker::isValid | ( | const ompl::base::State * | ompl_state | ) | const [pure virtual] |
Callback function used to determine whether a state is valid or not.
Implemented in ompl_ros_interface::OmplRosJointStateValidityChecker, and ompl_ros_interface::OmplRosTaskSpaceValidityChecker.
void ompl_ros_interface::OmplRosStateValidityChecker::printSettings | ( | std::ostream & | out | ) | const |
Used by the ROS space information to print information.
Definition at line 88 of file ompl_ros_state_validity_checker.cpp.
planning_environment::CollisionModelsInterface* ompl_ros_interface::OmplRosStateValidityChecker::collision_models_interface_ [protected] |
Definition at line 105 of file ompl_ros_state_validity_checker.h.
arm_navigation_msgs::ArmNavigationErrorCodes ompl_ros_interface::OmplRosStateValidityChecker::error_code_ [protected] |
Definition at line 110 of file ompl_ros_state_validity_checker.h.
planning_environment::KinematicConstraintEvaluatorSet ompl_ros_interface::OmplRosStateValidityChecker::goal_constraint_evaluator_set_ [protected] |
Definition at line 109 of file ompl_ros_state_validity_checker.h.
Definition at line 111 of file ompl_ros_state_validity_checker.h.
planning_models::KinematicState::JointStateGroup* ompl_ros_interface::OmplRosStateValidityChecker::joint_state_group_ [protected] |
Definition at line 104 of file ompl_ros_state_validity_checker.h.
planning_models::KinematicState* ompl_ros_interface::OmplRosStateValidityChecker::kinematic_state_ [protected] |
Definition at line 106 of file ompl_ros_state_validity_checker.h.
planning_environment::KinematicConstraintEvaluatorSet ompl_ros_interface::OmplRosStateValidityChecker::path_constraint_evaluator_set_ [protected] |
Definition at line 108 of file ompl_ros_state_validity_checker.h.