38#include <ompl/base/spaces/SE3StateSpace.h>
66 for (
const auto& it : m)
67 poses_.emplace_back(it.first, it.second);
71 RCLCPP_ERROR(getLogger(),
"No kinematics solvers specified. Unable to construct a "
72 "PoseModelStateSpace");
76 std::sort(poses_.begin(), poses_.end());
91 for (
const auto& pose : poses_)
92 total += pose.state_space_->getMaximumExtent();
101 state->poses =
new ompl::base::SE3StateSpace::StateType*[poses_.size()];
102 for (std::size_t i = 0; i < poses_.size(); ++i)
103 state->poses[i] = poses_[i].state_space_->allocState()->as<ompl::base::SE3StateSpace::StateType>();
109 for (std::size_t i = 0; i < poses_.size(); ++i)
110 poses_[i].state_space_->freeState(state->as<
StateType>()->
poses[i]);
120 for (std::size_t i = 0; i < poses_.size(); ++i)
129 ModelBasedStateSpace::sanityChecks(std::numeric_limits<double>::epsilon(), std::numeric_limits<double>::epsilon(),
130 ~ompl::base::StateSpace::STATESPACE_TRIANGLE_INEQUALITY);
134 ompl::base::State* state)
const
143 for (std::size_t i = 0; i < poses_.size(); ++i)
150 state->as<
StateType>()->setPoseComputed(
true);
158 if (d_cart > jump_factor_ * d_joint)
166 ompl::base::RealVectorBounds b(3);
173 for (
auto& pose : poses_)
174 pose.state_space_->as<ompl::base::SE3StateSpace>()->setBounds(b);
179 : subgroup_(subgroup), kinematics_solver_(k.allocator_(subgroup)), bijection_(k.bijection_)
181 state_space_ = std::make_shared<ompl::base::SE3StateSpace>();
182 state_space_->setName(subgroup_->getName() +
"_Workspace");
183 fk_link_.resize(1, kinematics_solver_->getTipFrame());
184 if (!fk_link_[0].empty() && fk_link_[0][0] ==
'/')
185 fk_link_[0] = fk_link_[0].substr(1);
188bool PoseModelStateSpace::PoseComponent::computeStateFK(StateType* full_state,
unsigned int idx)
const
191 std::vector<double> values(bijection_.size());
192 for (
unsigned int i = 0; i < bijection_.size(); ++i)
193 values[i] = full_state->values[bijection_[i]];
196 std::vector<geometry_msgs::msg::Pose> poses;
197 if (!kinematics_solver_->getPositionFK(fk_link_, values, poses))
201 ompl::base::SE3StateSpace::StateType* se3_state = full_state->poses[idx];
202 se3_state->setXYZ(poses[0].position.x, poses[0].position.y, poses[0].position.z);
203 ompl::base::SO3StateSpace::StateType& so3_state = se3_state->rotation();
204 so3_state.x = poses[0].orientation.x;
205 so3_state.y = poses[0].orientation.y;
206 so3_state.z = poses[0].orientation.z;
207 so3_state.w = poses[0].orientation.w;
212bool PoseModelStateSpace::PoseComponent::computeStateIK(StateType* full_state,
unsigned int idx)
const
215 std::vector<double> seed_values(bijection_.size());
216 for (std::size_t i = 0; i < bijection_.size(); ++i)
217 seed_values[i] = full_state->values[bijection_[i]];
227 geometry_msgs::msg::Pose pose;
228 const ompl::base::SE3StateSpace::StateType* se3_state = full_state->poses[idx];
229 pose.position.x = se3_state->getX();
230 pose.position.y = se3_state->getY();
231 pose.position.z = se3_state->getZ();
232 const ompl::base::SO3StateSpace::StateType& so3_state = se3_state->rotation();
233 pose.orientation.x = so3_state.x;
234 pose.orientation.y = so3_state.y;
235 pose.orientation.z = so3_state.z;
236 pose.orientation.w = so3_state.w;
239 std::vector<double> solution(bijection_.size());
240 moveit_msgs::msg::MoveItErrorCodes err_code;
241 if (!kinematics_solver_->getPositionIK(pose, seed_values, solution, err_code))
243 if (err_code.val != moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT ||
244 !kinematics_solver_->searchPositionIK(pose, seed_values, kinematics_solver_->getDefaultTimeout() * 2.0,
249 for (std::size_t i = 0; i < bijection_.size(); ++i)
250 full_state->values[bijection_[i]] = solution[i];
259 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)
283 state->as<
StateType>()->setJointsComputed(
true);
301 class PoseModelStateSampler :
public ompl::base::StateSampler
304 PoseModelStateSampler(
const ompl::base::StateSpace* space, ompl::base::StateSamplerPtr sampler)
305 : ompl::base::StateSampler(space), sampler_(std::move(sampler))
309 void sampleUniform(ompl::base::State* state)
override
311 sampler_->sampleUniform(state);
312 afterStateSample(state);
315 void sampleUniformNear(ompl::base::State* state,
const ompl::base::State* near,
const double distance)
override
317 sampler_->sampleUniformNear(state, near, distance);
318 afterStateSample(state);
321 void sampleGaussian(ompl::base::State* state,
const ompl::base::State* mean,
const double stdDev)
override
323 sampler_->sampleGaussian(state, mean, stdDev);
324 afterStateSample(state);
328 void afterStateSample(ompl::base::State* sample)
const
330 sample->as<
StateType>()->setJointsComputed(
true);
331 sample->as<
StateType>()->setPoseComputed(
false);
335 ompl::base::StateSamplerPtr sampler_;
338 return ompl::base::StateSamplerPtr(
static_cast<ompl::base::StateSampler*
>(
345 state->as<
StateType>()->setJointsComputed(
true);
346 state->as<
StateType>()->setPoseComputed(
false);
const std::pair< KinematicsSolver, KinematicsSolverMap > & getGroupKinematics() const
std::map< const JointModelGroup *, KinematicsSolver > KinematicsSolverMap
Map from group instances to allocator functions & bijections.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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.
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
void freeState(ompl::base::State *state) const override
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
virtual void copyToOMPLState(ompl::base::State *state, const moveit::core::RobotState &rstate) const
Copy the data from a set of joint states to an OMPL state.
unsigned int variable_count_
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
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
PoseModelStateSpace(const ModelBasedStateSpaceSpecification &spec)
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
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
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
The MoveIt interface to OMPL.
const moveit::core::JointModelGroup * joint_model_group_