38 #include <ompl/base/spaces/SE3StateSpace.h>
45 constexpr
char LOGNAME[] =
"pose_model_state_space";
60 for (
const auto& it : m)
61 poses_.emplace_back(it.first, it.second);
65 "PoseModelStateSpace");
74 const ompl::base::State* state2)
const
82 for (
const auto& pose : poses_)
83 total += pose.state_space_->getMaximumExtent();
91 new double[variable_count_];
92 state->poses =
new ompl::base::SE3StateSpace::StateType*[poses_.size()];
93 for (std::size_t i = 0; i < poses_.size(); ++i)
94 state->poses[i] = poses_[i].state_space_->allocState()->as<ompl::base::SE3StateSpace::StateType>();
100 for (std::size_t i = 0; i < poses_.size(); ++i)
101 poses_[i].state_space_->freeState(state->as<
StateType>()->
poses[i]);
107 const ompl::base::State* source)
const
112 for (std::size_t i = 0; i < poses_.size(); ++i)
116 computeStateK(destination);
121 ModelBasedStateSpace::sanityChecks(std::numeric_limits<double>::epsilon(), std::numeric_limits<float>::epsilon(),
122 ~ompl::base::StateSpace::STATESPACE_TRIANGLE_INEQUALITY);
126 const double t, ompl::base::State* state)
const
137 for (std::size_t i = 0; i < poses_.size(); ++i)
142 state->as<
StateType>()->setPoseComputed(
true);
145 if (computeStateIK(state))
150 if (d_cart > jump_factor_ * d_joint)
156 double minZ,
double maxZ)
159 ompl::base::RealVectorBounds b(3);
166 for (
auto& pose : poses_)
167 pose.state_space_->as<ompl::base::SE3StateSpace>()->setBounds(b);
172 : subgroup_(subgroup), kinematics_solver_(k.allocator_(subgroup)), bijection_(k.bijection_)
174 state_space_ = std::make_shared<ompl::base::SE3StateSpace>();
184 std::vector<double>
values(bijection_.size());
185 for (
unsigned int i = 0; i < bijection_.size(); ++i)
189 std::vector<geometry_msgs::Pose> poses;
190 if (!kinematics_solver_->getPositionFK(fk_link_,
values, poses))
194 ompl::base::SE3StateSpace::StateType* se3_state = full_state->
poses[idx];
195 se3_state->setXYZ(poses[0].position.x, poses[0].position.y, poses[0].position.z);
196 ompl::base::SO3StateSpace::StateType& so3_state = se3_state->rotation();
197 so3_state.x = poses[0].orientation.x;
198 so3_state.y = poses[0].orientation.y;
199 so3_state.z = poses[0].orientation.z;
200 so3_state.w = poses[0].orientation.w;
208 std::vector<double> seed_values(bijection_.size());
209 for (std::size_t i = 0; i < bijection_.size(); ++i)
210 seed_values[i] = full_state->
values[bijection_[i]];
220 geometry_msgs::Pose pose;
221 const ompl::base::SE3StateSpace::StateType* se3_state = full_state->
poses[idx];
222 pose.position.x = se3_state->getX();
223 pose.position.y = se3_state->getY();
224 pose.position.z = se3_state->getZ();
225 const ompl::base::SO3StateSpace::StateType& so3_state = se3_state->rotation();
226 pose.orientation.x = so3_state.x;
227 pose.orientation.y = so3_state.y;
228 pose.orientation.z = so3_state.z;
229 pose.orientation.w = so3_state.w;
232 std::vector<double> solution(bijection_.size());
233 moveit_msgs::MoveItErrorCodes err_code;
234 if (!kinematics_solver_->getPositionIK(pose, seed_values, solution, err_code))
236 if (err_code.val != moveit_msgs::MoveItErrorCodes::TIMED_OUT ||
237 !kinematics_solver_->searchPositionIK(pose, seed_values, kinematics_solver_->getDefaultTimeout() * 2.0,
242 for (std::size_t i = 0; i < bijection_.size(); ++i)
243 full_state->
values[bijection_[i]] = solution[i];
252 for (std::size_t i = 0; i <
poses_.size(); ++i)
258 state->as<
StateType>()->setPoseComputed(
true);
266 for (std::size_t i = 0; i <
poses_.size(); ++i)
272 state->as<
StateType>()->setJointsComputed(
true);
290 class PoseModelStateSampler :
public ompl::base::StateSampler
293 PoseModelStateSampler(
const ompl::base::StateSpace* space, ompl::base::StateSamplerPtr sampler)
294 : ompl::base::StateSampler(space), sampler_(std::move(sampler))
298 void sampleUniform(ompl::base::State* state)
override
300 sampler_->sampleUniform(state);
301 afterStateSample(state);
304 void sampleUniformNear(ompl::base::State* state,
const ompl::base::State* near,
const double distance)
override
306 sampler_->sampleUniformNear(state, near,
distance);
307 afterStateSample(state);
310 void sampleGaussian(ompl::base::State* state,
const ompl::base::State* mean,
const double stdDev)
override
312 sampler_->sampleGaussian(state, mean, stdDev);
313 afterStateSample(state);
317 void afterStateSample(ompl::base::State* sample)
const
319 sample->as<
StateType>()->setJointsComputed(
true);
320 sample->as<
StateType>()->setPoseComputed(
false);
324 ompl::base::StateSamplerPtr sampler_;
327 return ompl::base::StateSamplerPtr(
static_cast<ompl::base::StateSampler*
>(
335 state->as<
StateType>()->setJointsComputed(
true);
336 state->as<
StateType>()->setPoseComputed(
false);