pose_model_state_space.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
38 #include <ompl/base/spaces/SE3StateSpace.h>
40 
41 #include <utility>
42 
43 namespace ompl_interface
44 {
45 constexpr char LOGNAME[] = "pose_model_state_space";
46 } // namespace ompl_interface
47 
49 
51  : ModelBasedStateSpace(spec)
52 {
53  jump_factor_ = 1.5; // \todo make this a param
54 
55  if (spec.joint_model_group_->getGroupKinematics().first)
56  poses_.emplace_back(spec.joint_model_group_, spec.joint_model_group_->getGroupKinematics().first);
57  else if (!spec.joint_model_group_->getGroupKinematics().second.empty())
58  {
60  for (const auto& it : m)
61  poses_.emplace_back(it.first, it.second);
62  }
63  if (poses_.empty())
64  ROS_ERROR_NAMED(LOGNAME, "No kinematics solvers specified. Unable to construct a "
65  "PoseModelStateSpace");
66  else
67  std::sort(poses_.begin(), poses_.end());
68  setName(getName() + "_" + PARAMETERIZATION_TYPE);
69 }
70 
72 
73 double ompl_interface::PoseModelStateSpace::distance(const ompl::base::State* state1,
74  const ompl::base::State* state2) const
75 {
76  return ModelBasedStateSpace::distance(state1, state2);
77 }
78 
80 {
81  double total = 0.0;
82  for (const auto& pose : poses_)
83  total += pose.state_space_->getMaximumExtent();
84  return total;
85 }
86 
88 {
89  auto* state = new StateType();
90  state->values =
91  new double[variable_count_]; // need to allocate this here since ModelBasedStateSpace::allocState() is not called
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>();
95  return state;
96 }
97 
98 void ompl_interface::PoseModelStateSpace::freeState(ompl::base::State* state) const
99 {
100  for (std::size_t i = 0; i < poses_.size(); ++i)
101  poses_[i].state_space_->freeState(state->as<StateType>()->poses[i]);
102  delete[] state->as<StateType>()->poses;
104 }
105 
106 void ompl_interface::PoseModelStateSpace::copyState(ompl::base::State* destination,
107  const ompl::base::State* source) const
108 {
109  // copy the state data
110  ModelBasedStateSpace::copyState(destination, source);
111 
112  for (std::size_t i = 0; i < poses_.size(); ++i)
113  poses_[i].state_space_->copyState(destination->as<StateType>()->poses[i], source->as<StateType>()->poses[i]);
114 
115  // compute additional stuff if needed
116  computeStateK(destination);
117 }
118 
120 {
121  ModelBasedStateSpace::sanityChecks(std::numeric_limits<double>::epsilon(), std::numeric_limits<float>::epsilon(),
122  ~ompl::base::StateSpace::STATESPACE_TRIANGLE_INEQUALITY);
123 }
124 
125 void ompl_interface::PoseModelStateSpace::interpolate(const ompl::base::State* from, const ompl::base::State* to,
126  const double t, ompl::base::State* state) const
127 {
128  // moveit::Profiler::ScopedBlock sblock("interpolate");
129 
130  // we want to interpolate in Cartesian space to avoid rejection of path constraints
131 
132  // interpolate in joint space to find a suitable seed for IK
133  ModelBasedStateSpace::interpolate(from, to, t, state);
134  double d_joint = ModelBasedStateSpace::distance(from, state);
135 
136  // interpolate SE3 components
137  for (std::size_t i = 0; i < poses_.size(); ++i)
138  poses_[i].state_space_->interpolate(from->as<StateType>()->poses[i], to->as<StateType>()->poses[i], t,
139  state->as<StateType>()->poses[i]);
140 
141  // the call above may reset all flags for state; but we know the pose we want flag should be set
142  state->as<StateType>()->setPoseComputed(true);
143 
144  // compute IK for interpolated Cartesian state
145  if (computeStateIK(state))
146  {
147  double d_cart = ModelBasedStateSpace::distance(from, state);
148 
149  // reject if Cartesian interpolation yields much larger distance than joint interpolation
150  if (d_cart > jump_factor_ * d_joint)
151  state->as<StateType>()->markInvalid();
152  }
153 }
154 
155 void ompl_interface::PoseModelStateSpace::setPlanningVolume(double minX, double maxX, double minY, double maxY,
156  double minZ, double maxZ)
157 {
158  ModelBasedStateSpace::setPlanningVolume(minX, maxX, minY, maxY, minZ, maxZ);
159  ompl::base::RealVectorBounds b(3);
160  b.low[0] = minX;
161  b.low[1] = minY;
162  b.low[2] = minZ;
163  b.high[0] = maxX;
164  b.high[1] = maxY;
165  b.high[2] = maxZ;
166  for (auto& pose : poses_)
167  pose.state_space_->as<ompl::base::SE3StateSpace>()->setBounds(b);
168 }
169 
172  : subgroup_(subgroup), kinematics_solver_(k.allocator_(subgroup)), bijection_(k.bijection_)
173 {
174  state_space_ = std::make_shared<ompl::base::SE3StateSpace>();
175  state_space_->setName(subgroup_->getName() + "_Workspace");
176  fk_link_.resize(1, kinematics_solver_->getTipFrame());
177  if (!fk_link_[0].empty() && fk_link_[0][0] == '/')
178  fk_link_[0] = fk_link_[0].substr(1);
179 }
180 
182 {
183  // read the values from the joint state, in the order expected by the kinematics solver
184  std::vector<double> values(bijection_.size());
185  for (unsigned int i = 0; i < bijection_.size(); ++i)
186  values[i] = full_state->values[bijection_[i]];
187 
188  // compute forward kinematics for the link of interest
189  std::vector<geometry_msgs::Pose> poses;
190  if (!kinematics_solver_->getPositionFK(fk_link_, values, poses))
191  return false;
192 
193  // copy the resulting data to the desired location in the state
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;
201 
202  return true;
203 }
204 
206 {
207  // read the values from the joint state, in the order expected by the kinematics solver; use these as the seed
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]];
211 
212  /*
213  std::cout << "seed: ";
214  for (std::size_t i = 0 ; i < seed_values.size() ; ++i)
215  std::cout << seed_values[i] << " ";
216  std::cout << std::endl;
217  */
218 
219  // construct the pose
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;
230 
231  // run IK
232  std::vector<double> solution(bijection_.size());
233  moveit_msgs::MoveItErrorCodes err_code;
234  if (!kinematics_solver_->getPositionIK(pose, seed_values, solution, err_code))
235  {
236  if (err_code.val != moveit_msgs::MoveItErrorCodes::TIMED_OUT ||
237  !kinematics_solver_->searchPositionIK(pose, seed_values, kinematics_solver_->getDefaultTimeout() * 2.0,
238  solution, err_code))
239  return false;
240  }
241 
242  for (std::size_t i = 0; i < bijection_.size(); ++i)
243  full_state->values[bijection_[i]] = solution[i];
244 
245  return true;
246 }
247 
248 bool ompl_interface::PoseModelStateSpace::computeStateFK(ompl::base::State* state) const
249 {
250  if (state->as<StateType>()->poseComputed())
251  return true;
252  for (std::size_t i = 0; i < poses_.size(); ++i)
253  if (!poses_[i].computeStateFK(state->as<StateType>(), i))
254  {
255  state->as<StateType>()->markInvalid();
256  return false;
257  }
258  state->as<StateType>()->setPoseComputed(true);
259  return true;
260 }
261 
262 bool ompl_interface::PoseModelStateSpace::computeStateIK(ompl::base::State* state) const
263 {
264  if (state->as<StateType>()->jointsComputed())
265  return true;
266  for (std::size_t i = 0; i < poses_.size(); ++i)
267  if (!poses_[i].computeStateIK(state->as<StateType>(), i))
268  {
269  state->as<StateType>()->markInvalid();
270  return false;
271  }
272  state->as<StateType>()->setJointsComputed(true);
273  return true;
274 }
275 
276 bool ompl_interface::PoseModelStateSpace::computeStateK(ompl::base::State* state) const
277 {
278  if (state->as<StateType>()->jointsComputed() && !state->as<StateType>()->poseComputed())
279  return computeStateFK(state);
280  if (!state->as<StateType>()->jointsComputed() && state->as<StateType>()->poseComputed())
281  return computeStateIK(state);
282  if (state->as<StateType>()->jointsComputed() && state->as<StateType>()->poseComputed())
283  return true;
284  state->as<StateType>()->markInvalid();
285  return false;
286 }
287 
289 {
290  class PoseModelStateSampler : public ompl::base::StateSampler
291  {
292  public:
293  PoseModelStateSampler(const ompl::base::StateSpace* space, ompl::base::StateSamplerPtr sampler)
294  : ompl::base::StateSampler(space), sampler_(std::move(sampler))
295  {
296  }
297 
298  void sampleUniform(ompl::base::State* state) override
299  {
300  sampler_->sampleUniform(state);
301  afterStateSample(state);
302  }
303 
304  void sampleUniformNear(ompl::base::State* state, const ompl::base::State* near, const double distance) override
305  {
306  sampler_->sampleUniformNear(state, near, distance);
307  afterStateSample(state);
308  }
309 
310  void sampleGaussian(ompl::base::State* state, const ompl::base::State* mean, const double stdDev) override
311  {
312  sampler_->sampleGaussian(state, mean, stdDev);
313  afterStateSample(state);
314  }
315 
316  protected:
317  void afterStateSample(ompl::base::State* sample) const
318  {
319  sample->as<StateType>()->setJointsComputed(true);
320  sample->as<StateType>()->setPoseComputed(false);
321  space_->as<PoseModelStateSpace>()->computeStateFK(sample);
322  }
323 
324  ompl::base::StateSamplerPtr sampler_;
325  };
326 
327  return ompl::base::StateSamplerPtr(static_cast<ompl::base::StateSampler*>(
328  new PoseModelStateSampler(this, ModelBasedStateSpace::allocDefaultStateSampler())));
329 }
330 
332  const moveit::core::RobotState& rstate) const
333 {
335  state->as<StateType>()->setJointsComputed(true);
336  state->as<StateType>()->setPoseComputed(false);
337  computeStateFK(state);
338  /*
339  std::cout << "COPY STATE IN:\n";
340  printState(state, std::cout);
341  std::cout << "---------- COPY STATE IN\n"; */
342 }
ompl_interface::ModelBasedStateSpace::StateType::values
double * values
Definition: model_based_state_space.h:195
ompl_interface::PoseModelStateSpace::distance
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
Definition: pose_model_state_space.cpp:73
moveit::core::JointModelGroup::KinematicsSolver
ompl_interface::PoseModelStateSpace::PoseComponent::subgroup_
const moveit::core::JointModelGroup * subgroup_
Definition: pose_model_state_space.h:196
ompl_interface::PoseModelStateSpace::computeStateK
bool computeStateK(ompl::base::State *state) const
Definition: pose_model_state_space.cpp:276
ompl_interface::ModelBasedStateSpace::freeState
void freeState(ompl::base::State *state) const override
Definition: model_based_state_space.cpp:111
moveit::core::JointModelGroup::getGroupKinematics
const std::pair< KinematicsSolver, KinematicsSolverMap > & getGroupKinematics() const
ompl_interface::PoseModelStateSpace::StateType
Definition: pose_model_state_space.h:113
ompl_interface::PoseModelStateSpace::computeStateFK
bool computeStateFK(ompl::base::State *state) const
Definition: pose_model_state_space.cpp:248
ompl_interface::PoseModelStateSpace::PARAMETERIZATION_TYPE
static const std::string PARAMETERIZATION_TYPE
Definition: pose_model_state_space.h:111
ompl_interface::PoseModelStateSpace::StateType::poses
ompl::base::SE3StateSpace::StateType ** poses
Definition: pose_model_state_space.h:153
ompl_interface::PoseModelStateSpace::allocDefaultStateSampler
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
Definition: pose_model_state_space.cpp:288
ompl_interface::ModelBasedStateSpace::interpolate
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
Definition: model_based_state_space.cpp:199
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
ompl_interface::ModelBasedStateSpaceSpecification
Definition: model_based_state_space.h:84
ompl_interface::PoseModelStateSpace::StateType::jointsComputed
bool jointsComputed() const
Definition: pose_model_state_space.h:127
ompl_interface::ModelBasedStateSpace::distance
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
Definition: model_based_state_space.cpp:169
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
ompl_interface::PoseModelStateSpace::PoseComponent::fk_link_
std::vector< std::string > fk_link_
Definition: pose_model_state_space.h:200
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
ompl_interface::PoseModelStateSpace::computeStateIK
bool computeStateIK(ompl::base::State *state) const
Definition: pose_model_state_space.cpp:262
ompl_interface::PoseModelStateSpace::StateType::poseComputed
bool poseComputed() const
Definition: pose_model_state_space.h:132
ompl_interface::ModelBasedStateSpace::copyToOMPLState
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.
Definition: model_based_state_space.cpp:328
ompl_interface::PoseModelStateSpace::allocState
ompl::base::State * allocState() const override
Definition: pose_model_state_space.cpp:87
ompl_interface::PoseModelStateSpace::~PoseModelStateSpace
~PoseModelStateSpace() override
ompl_interface::ModelBasedStateSpaceSpecification::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: model_based_state_space.h:100
moveit::core::JointModelGroup::getName
const std::string & getName() const
ompl_interface::PoseModelStateSpace::PoseComponent::kinematics_solver_
kinematics::KinematicsBasePtr kinematics_solver_
Definition: pose_model_state_space.h:197
pose_model_state_space.h
moveit::core::JointModelGroup::KinematicsSolverMap
std::map< const JointModelGroup *, KinematicsSolver > KinematicsSolverMap
ompl_interface::PoseModelStateSpace::freeState
void freeState(ompl::base::State *state) const override
Definition: pose_model_state_space.cpp:98
ompl_interface::LOGNAME
constexpr char LOGNAME[]
Definition: constrained_goal_sampler.cpp:78
ompl_interface::PoseModelStateSpace::interpolate
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
Definition: pose_model_state_space.cpp:125
ompl_interface::ModelBasedStateSpace::allocDefaultStateSampler
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
Definition: model_based_state_space.cpp:251
ompl_interface::PoseModelStateSpace::copyState
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
Definition: pose_model_state_space.cpp:106
ompl_interface::PoseModelStateSpace::poses_
std::vector< PoseComponent > poses_
Definition: pose_model_state_space.h:203
ompl_interface::ModelBasedStateSpace::copyState
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
Definition: model_based_state_space.cpp:117
ompl_interface::ModelBasedStateSpace
Definition: model_based_state_space.h:106
ompl_interface::PoseModelStateSpace::PoseModelStateSpace
PoseModelStateSpace(const ModelBasedStateSpaceSpecification &spec)
Definition: pose_model_state_space.cpp:50
ompl_interface::PoseModelStateSpace::copyToOMPLState
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.
Definition: pose_model_state_space.cpp:331
ompl_interface::PoseModelStateSpace::getMaximumExtent
double getMaximumExtent() const override
Definition: pose_model_state_space.cpp:79
values
std::vector< double > values
ompl_interface::PoseModelStateSpace::sanityChecks
void sanityChecks() const override
Definition: pose_model_state_space.cpp:119
ompl_interface::PoseModelStateSpace::PoseComponent::PoseComponent
PoseComponent(const moveit::core::JointModelGroup *subgroup, const moveit::core::JointModelGroup::KinematicsSolver &k)
Definition: pose_model_state_space.cpp:170
ompl_interface::PoseModelStateSpace::PoseComponent::computeStateIK
bool computeStateIK(StateType *full_state, unsigned int idx) const
Definition: pose_model_state_space.cpp:205
ompl_interface::PoseModelStateSpace::jump_factor_
double jump_factor_
Definition: pose_model_state_space.h:204
moveit::core::JointModelGroup
profiler.h
ompl_interface::ModelBasedStateSpace::setPlanningVolume
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.
Definition: model_based_state_space.cpp:229
ompl_interface::PoseModelStateSpace
Definition: pose_model_state_space.h:76
ompl_interface::PoseModelStateSpace::PoseComponent::computeStateFK
bool computeStateFK(StateType *full_state, unsigned int idx) const
Definition: pose_model_state_space.cpp:181
t
geometry_msgs::TransformStamped t
ompl_interface::PoseModelStateSpace::setPlanningVolume
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.
Definition: pose_model_state_space.cpp:155
ompl_interface::PoseModelStateSpace::PoseComponent::state_space_
ompl::base::StateSpacePtr state_space_
Definition: pose_model_state_space.h:199


ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:10