40#include <ompl/base/spaces/SE3StateSpace.h>
81 flags &= ~JOINTS_COMPUTED;
93 flags &= ~POSE_COMPUTED;
97 ompl::base::SE3StateSpace::StateType**
poses;
103 ompl::base::State*
allocState()
const override;
104 void freeState(ompl::base::State* state)
const override;
105 void copyState(ompl::base::State* destination,
const ompl::base::State* source)
const override;
106 void interpolate(
const ompl::base::State* from,
const ompl::base::State* to,
const double t,
107 ompl::base::State* state)
const override;
108 double distance(
const ompl::base::State* state1,
const ompl::base::State* state2)
const override;
117 void setPlanningVolume(
double minX,
double maxX,
double minY,
double maxY,
double minZ,
double maxZ)
override;
132 bool computeStateFK(StateType* full_state,
unsigned int idx)
const;
133 bool computeStateIK(StateType* full_state,
unsigned int idx)
const;
135 bool operator<(
const PoseComponent& o)
const
137 return subgroup_->getName() < o.subgroup_->getName();
141 kinematics::KinematicsBasePtr kinematics_solver_;
142 std::vector<size_t> bijection_;
143 ompl::base::StateSpacePtr state_space_;
144 std::vector<std::string> fk_link_;
147 std::vector<PoseComponent> poses_;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointsComputed(bool value)
void setPoseComputed(bool value)
bool jointsComputed() const
bool poseComputed() const
ompl::base::SE3StateSpace::StateType ** poses
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
ompl::base::State * allocState() const override
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ) override
Set the planning volume for the possible SE2 and/or SE3 components of the state space.
void sanityChecks() const override
const std::string & getParameterizationType() const override
double getMaximumExtent() const override
bool computeStateFK(ompl::base::State *state) const
void copyToOMPLState(ompl::base::State *state, const moveit::core::RobotState &rstate) const override
Copy the data from a set of joint states to an OMPL state.
bool computeStateK(ompl::base::State *state) const
void freeState(ompl::base::State *state) const override
static const std::string PARAMETERIZATION_TYPE
~PoseModelStateSpace() override
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
bool computeStateIK(ompl::base::State *state) const
The MoveIt interface to OMPL.