Go to the documentation of this file.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
00035
00036
00037 #ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_JOINT_STATE_SPACE_
00038 #define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_JOINT_STATE_SPACE_
00039
00040 #include <ompl/base/StateSpace.h>
00041 #include <moveit/robot_model/robot_model.h>
00042 #include <moveit/robot_state/robot_state.h>
00043
00044 namespace ompl_interface
00045 {
00046
00047 class ModelBasedJointStateSpace : public ompl::base::StateSpace
00048 {
00049 public:
00050
00051 class StateType : public ompl::base::State
00052 {
00053 public:
00054 robot_state::JointState *joint_state;
00055 };
00056
00057 ModelBasedJointStateSpace(const robot_model::JointModel *joint_model);
00058 ModelBasedJointStateSpace(const robot_model::JointModel *joint_model,
00059 const robot_model::JointModel::Bounds &joint_bounds);
00060
00061 virtual ~ModelBasedJointStateSpace();
00062
00063 virtual ompl::base::State* allocState() const;
00064 virtual void freeState(ompl::base::State *state) const;
00065
00066 virtual unsigned int getDimension() const;
00067 virtual double getMaximumExtent() const;
00068 virtual void enforceBounds(ompl::base::State *state) const;
00069 virtual bool satisfiesBounds(const ompl::base::State *state) const;
00070
00071 virtual void copyState(ompl::base::State *destination, const ompl::base::State *source) const;
00072 virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const;
00073 virtual bool equalStates(const ompl::base::State *state1, const ompl::base::State *state2) const;
00074 virtual void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const;
00075
00076 virtual unsigned int getSerializationLength() const;
00077 virtual void serialize(void *serialization, const ompl::base::State *state) const;
00078 virtual void deserialize(ompl::base::State *state, const void *serialization) const;
00079 virtual double* getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const;
00080 virtual void printState(const ompl::base::State *state, std::ostream &out) const;
00081 virtual void printSettings(std::ostream &out) const;
00082
00083 virtual ompl::base::StateSamplerPtr allocDefaultStateSampler() const;
00084
00085 const robot_model::JointModel* getJointModel() const
00086 {
00087 return joint_model_;
00088 }
00089
00090 const std::string& getJointName() const
00091 {
00092 return getJointModel()->getName();
00093 }
00094
00096 void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ);
00097
00098 const robot_model::JointModel::Bounds& getJointBounds() const
00099 {
00100 return joint_bounds_;
00101 }
00102
00103 protected:
00104
00105 void propagateJointStateUpdate(ompl::base::State *state) const;
00106
00107 const robot_model::JointModel *joint_model_;
00108 robot_model::JointModel::Bounds joint_bounds_;
00109
00110 };
00111
00112 }
00113
00114 #endif