00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #ifndef OMPL_ROS_STATE_VALIDITY_CHECKER_
00038 #define OMPL_ROS_STATE_VALIDITY_CHECKER_
00039
00040 #include <planning_environment/monitors/planning_monitor.h>
00041 #include <planning_environment/util/kinematic_state_constraint_evaluator.h>
00042 #include <motion_planning_msgs/GetMotionPlan.h>
00043
00044 #include <ompl_ros_interface/helpers/ompl_ros_conversions.h>
00045
00046 #include <ompl/base/StateValidityChecker.h>
00047 #include <ompl/base/State.h>
00048
00049
00050 namespace ompl_ros_interface
00051 {
00056 class OmplRosStateValidityChecker : public ompl::base::StateValidityChecker
00057 {
00058 public:
00064 OmplRosStateValidityChecker(ompl::base::SpaceInformation *si,
00065 planning_environment::PlanningMonitor *planning_monitor) :
00066 ompl::base::StateValidityChecker(si),
00067 planning_monitor_(planning_monitor)
00068 {
00069 }
00070
00072 virtual bool isValid (const ompl::base::State *ompl_state) const = 0;
00073
00075 void printSettings(std::ostream &out) const;
00076
00077
00078
00079
00080
00081
00082
00083
00084 virtual void configureOnRequest(planning_models::KinematicState *kinematic_state,
00085 planning_models::KinematicState::JointStateGroup *physical_joint_state_group,
00086 const motion_planning_msgs::GetMotionPlan::Request &request);
00087
00088
00089
00090
00091
00092 motion_planning_msgs::ArmNavigationErrorCodes getLastErrorCode()
00093 {
00094 return error_code_;
00095 }
00096
00097
00098
00099
00100
00101 virtual bool isStateValid(const ompl::base::State *ompl_state) = 0;
00102
00103 protected:
00104 planning_models::KinematicState::JointStateGroup *joint_state_group_;
00105 planning_environment::PlanningMonitor *planning_monitor_;
00106 planning_models::KinematicState *kinematic_state_;
00107
00108 planning_environment::KinematicConstraintEvaluatorSet path_constraint_evaluator_set_;
00109 planning_environment::KinematicConstraintEvaluatorSet goal_constraint_evaluator_set_;
00110 motion_planning_msgs::ArmNavigationErrorCodes error_code_;
00111 sensor_msgs::JointState joint_state_;
00112 motion_planning_msgs::Constraints getPhysicalConstraints(const motion_planning_msgs::Constraints &constraints);
00113 };
00114
00115 typedef boost::shared_ptr<ompl_ros_interface::OmplRosStateValidityChecker> OmplRosStateValidityCheckerPtr;
00116
00117 }
00118
00119 #endif
00120