37 #ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_ 38 #define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_ 41 #include <ompl/base/spaces/SE3StateSpace.h> 90 ompl::base::SE3StateSpace::StateType**
poses;
97 virtual void freeState(ompl::base::State* state)
const;
98 virtual void copyState(ompl::base::State* destination,
const ompl::base::State* source)
const;
99 virtual void interpolate(
const ompl::base::State* from,
const ompl::base::State* to,
const double t,
100 ompl::base::State* state)
const;
101 virtual double distance(
const ompl::base::State* state1,
const ompl::base::State* state2)
const;
110 virtual void setPlanningVolume(
double minX,
double maxX,
double minY,
double maxY,
double minZ,
double maxZ);
111 virtual void copyToOMPLState(ompl::base::State* state,
const robot_state::RobotState& rstate)
const;
118 const robot_model::JointModelGroup::KinematicsSolver& k);
125 return subgroup_->getName() < o.
subgroup_->getName();
virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
Set the planning volume for the possible SE2 and/or SE3 components of the state space.
virtual ompl::base::StateSamplerPtr allocDefaultStateSampler() const
void setJointsComputed(bool value)
static const std::string PARAMETERIZATION_TYPE
bool computeStateK(ompl::base::State *state) const
The MoveIt! interface to OMPL.
ompl::base::SE3StateSpace::StateType ** poses
bool poseComputed() const
std::vector< std::string > fk_link_
virtual void copyState(ompl::base::State *destination, const ompl::base::State *source) const
void setPoseComputed(bool value)
std::vector< PoseComponent > poses_
bool jointsComputed() const
virtual ompl::base::State * allocState() const
kinematics::KinematicsBasePtr kinematics_solver_
bool computeStateIK(ompl::base::State *state) const
std::vector< unsigned int > bijection_
virtual void copyToOMPLState(ompl::base::State *state, const robot_state::RobotState &rstate) const
Copy the data from a set of joint states to an OMPL state.
ompl::base::StateSpacePtr state_space_
PoseModelStateSpace(const ModelBasedStateSpaceSpecification &spec)
virtual ~PoseModelStateSpace()
virtual void sanityChecks() const
virtual double getMaximumExtent() const
bool computeStateFK(ompl::base::State *state) const
const robot_model::JointModelGroup * subgroup_
bool operator<(const PoseComponent &o) const
virtual void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const
virtual void freeState(ompl::base::State *state) const