38 #include <ompl/base/spaces/SE3StateSpace.h> 52 const robot_model::JointModelGroup::KinematicsSolverMap& m = spec.
joint_model_group_->getGroupKinematics().second;
53 for (robot_model::JointModelGroup::KinematicsSolverMap::const_iterator it = m.begin(); it != m.end(); ++it)
57 ROS_ERROR_NAMED(
"pose_model_state_space",
"No kinematics solvers specified. Unable to construct a " 58 "PoseModelStateSpace");
69 const ompl::base::State* state2)
const 72 for (std::size_t i = 0; i <
poses_.size(); ++i)
80 for (std::size_t i = 0; i <
poses_.size(); ++i)
81 total +=
poses_[i].state_space_->getMaximumExtent();
90 state->
poses =
new ompl::base::SE3StateSpace::StateType*[
poses_.size()];
91 for (std::size_t i = 0; i <
poses_.size(); ++i)
92 state->
poses[i] =
poses_[i].state_space_->allocState()->as<ompl::base::SE3StateSpace::StateType>();
98 for (std::size_t i = 0; i <
poses_.size(); ++i)
105 const ompl::base::State* source)
const 110 for (std::size_t i = 0; i <
poses_.size(); ++i)
119 ModelBasedStateSpace::sanityChecks(std::numeric_limits<double>::epsilon(), std::numeric_limits<float>::epsilon(),
120 ~ompl::base::StateSpace::STATESPACE_TRIANGLE_INEQUALITY);
124 const double t, ompl::base::State* state)
const 135 for (std::size_t i = 0; i <
poses_.size(); ++i)
140 state->as<
StateType>()->setPoseComputed(
true);
159 if (d_from + d_to > std::max(0.2, dj))
165 double minZ,
double maxZ)
168 ompl::base::RealVectorBounds b(3);
175 for (std::size_t i = 0; i <
poses_.size(); ++i)
176 poses_[i].state_space_->as<ompl::base::SE3StateSpace>()->setBounds(b);
180 const robot_model::JointModelGroup* subgroup,
const robot_model::JointModelGroup::KinematicsSolver& k)
181 : subgroup_(subgroup), kinematics_solver_(k.allocator_(subgroup)), bijection_(k.bijection_)
194 for (
unsigned int i = 0; i <
bijection_.size(); ++i)
198 std::vector<geometry_msgs::Pose> poses;
203 ompl::base::SE3StateSpace::StateType* se3_state = full_state->
poses[idx];
204 se3_state->setXYZ(poses[0].position.x, poses[0].position.y, poses[0].position.z);
205 ompl::base::SO3StateSpace::StateType& so3_state = se3_state->rotation();
206 so3_state.x = poses[0].orientation.x;
207 so3_state.y = poses[0].orientation.y;
208 so3_state.z = poses[0].orientation.z;
209 so3_state.w = poses[0].orientation.w;
217 std::vector<double> seed_values(
bijection_.size());
218 for (std::size_t i = 0; i <
bijection_.size(); ++i)
229 geometry_msgs::Pose pose;
230 const ompl::base::SE3StateSpace::StateType* se3_state = full_state->
poses[idx];
231 pose.position.x = se3_state->getX();
232 pose.position.y = se3_state->getY();
233 pose.position.z = se3_state->getZ();
234 const ompl::base::SO3StateSpace::StateType& so3_state = se3_state->rotation();
235 pose.orientation.x = so3_state.x;
236 pose.orientation.y = so3_state.y;
237 pose.orientation.z = so3_state.z;
238 pose.orientation.w = so3_state.w;
241 std::vector<double> solution(
bijection_.size());
242 moveit_msgs::MoveItErrorCodes err_code;
245 if (err_code.val != moveit_msgs::MoveItErrorCodes::TIMED_OUT ||
251 for (std::size_t i = 0; i <
bijection_.size(); ++i)
261 for (std::size_t i = 0; i <
poses_.size(); ++i)
267 state->as<
StateType>()->setPoseComputed(
true);
275 for (std::size_t i = 0; i <
poses_.size(); ++i)
281 state->as<
StateType>()->setJointsComputed(
true);
299 class PoseModelStateSampler :
public ompl::base::StateSampler
302 PoseModelStateSampler(
const ompl::base::StateSpace* space,
const ompl::base::StateSamplerPtr& sampler)
303 : ompl::base::StateSampler(space), sampler_(sampler)
307 virtual void sampleUniform(ompl::base::State* state)
309 sampler_->sampleUniform(state);
310 afterStateSample(state);
313 virtual void sampleUniformNear(ompl::base::State* state,
const ompl::base::State* near,
const double distance)
315 sampler_->sampleUniformNear(state, near, distance);
316 afterStateSample(state);
319 virtual void sampleGaussian(ompl::base::State* state,
const ompl::base::State* mean,
const double stdDev)
321 sampler_->sampleGaussian(state, mean, stdDev);
322 afterStateSample(state);
326 void afterStateSample(ompl::base::State* sample)
const 328 sample->as<
StateType>()->setJointsComputed(
true);
329 sample->as<
StateType>()->setPoseComputed(
false);
333 ompl::base::StateSamplerPtr sampler_;
336 return ompl::base::StateSamplerPtr(static_cast<ompl::base::StateSampler*>(
341 const robot_state::RobotState& rstate)
const 344 state->as<
StateType>()->setJointsComputed(
true);
345 state->as<
StateType>()->setPoseComputed(
false);
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
PoseComponent(const robot_model::JointModelGroup *subgroup, const robot_model::JointModelGroup::KinematicsSolver &k)
const robot_model::JointModelGroup * joint_model_group_
virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const
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.
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.
std::vector< double > values
bool computeStateFK(StateType *full_state, unsigned int idx) const
std::string getName(void *handle)
unsigned int variable_count_
virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const
static const std::string PARAMETERIZATION_TYPE
bool computeStateK(ompl::base::State *state) const
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
std::vector< PoseComponent > poses_
bool jointsComputed() const
virtual ompl::base::State * allocState() const
kinematics::KinematicsBasePtr kinematics_solver_
bool computeStateIK(ompl::base::State *state) const
virtual void freeState(ompl::base::State *state) const
virtual void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const
bool computeStateIK(StateType *full_state, unsigned int idx) const
std::vector< unsigned int > bijection_
virtual ompl::base::StateSamplerPtr allocDefaultStateSampler() const
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.
virtual void copyState(ompl::base::State *destination, const ompl::base::State *source) const
ompl::base::StateSpacePtr state_space_
#define ROS_ERROR_NAMED(name,...)
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_
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