This class implements a state validity checker in joint space. More...
#include <ompl_ros_joint_state_validity_checker.h>
Public Member Functions | |
virtual bool | isStateValid (const ompl::base::State *ompl_state) |
A non-const version of isValid designed to fill in the last error code. | |
virtual bool | isValid (const ompl::base::State *ompl_state) const |
The callback function used by the planners to determine if a state is valid. | |
OmplRosJointStateValidityChecker (ompl::base::SpaceInformation *si, planning_environment::PlanningMonitor *planning_monitor, const ompl_ros_interface::OmplStateToKinematicStateMapping &mapping) | |
Default constructor. | |
~OmplRosJointStateValidityChecker () | |
Protected Attributes | |
geometry_msgs::Pose | cached_transform_pose_ |
ompl_ros_interface::OmplStateToKinematicStateMapping | ompl_state_to_kinematic_state_mapping_ |
This class implements a state validity checker in joint space.
Definition at line 48 of file ompl_ros_joint_state_validity_checker.h.
ompl_ros_interface::OmplRosJointStateValidityChecker::OmplRosJointStateValidityChecker | ( | ompl::base::SpaceInformation * | si, | |
planning_environment::PlanningMonitor * | planning_monitor, | |||
const ompl_ros_interface::OmplStateToKinematicStateMapping & | mapping | |||
) | [inline] |
Default constructor.
si | - The space information for this validity checker | |
planning_monitor | - The planning monitor | |
mapping | - The mapping between the ompl state and the kinematic state that the planning monitor will use |
Definition at line 57 of file ompl_ros_joint_state_validity_checker.h.
ompl_ros_interface::OmplRosJointStateValidityChecker::~OmplRosJointStateValidityChecker | ( | ) | [inline] |
Definition at line 64 of file ompl_ros_joint_state_validity_checker.h.
bool ompl_ros_interface::OmplRosJointStateValidityChecker::isStateValid | ( | const ompl::base::State * | ompl_state | ) | [virtual] |
A non-const version of isValid designed to fill in the last error code.
ompl_state | The state that needs to be checked |
Implements ompl_ros_interface::OmplRosStateValidityChecker.
Definition at line 73 of file ompl_ros_joint_state_validity_checker.cpp.
bool ompl_ros_interface::OmplRosJointStateValidityChecker::isValid | ( | const ompl::base::State * | ompl_state | ) | const [virtual] |
The callback function used by the planners to determine if a state is valid.
ompl_state | The state that needs to be checked |
Implements ompl_ros_interface::OmplRosStateValidityChecker.
Definition at line 42 of file ompl_ros_joint_state_validity_checker.cpp.
geometry_msgs::Pose ompl_ros_interface::OmplRosJointStateValidityChecker::cached_transform_pose_ [protected] |
Definition at line 83 of file ompl_ros_joint_state_validity_checker.h.
ompl_ros_interface::OmplStateToKinematicStateMapping ompl_ros_interface::OmplRosJointStateValidityChecker::ompl_state_to_kinematic_state_mapping_ [protected] |
Definition at line 79 of file ompl_ros_joint_state_validity_checker.h.