moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
43namespace ompl_interface
44{
45namespace
46{
47rclcpp::Logger getLogger()
48{
49 return moveit::getLogger("moveit.planners.ompl.pose_model_state_space");
50}
51} // namespace
52
53const std::string PoseModelStateSpace::PARAMETERIZATION_TYPE = "PoseModel";
54
56{
57 jump_factor_ = 1.5; // \todo make this a param
58
59 if (spec.joint_model_group_->getGroupKinematics().first)
60 {
61 poses_.emplace_back(spec.joint_model_group_, spec.joint_model_group_->getGroupKinematics().first);
62 }
63 else if (!spec.joint_model_group_->getGroupKinematics().second.empty())
64 {
66 for (const auto& it : m)
67 poses_.emplace_back(it.first, it.second);
68 }
69 if (poses_.empty())
70 {
71 RCLCPP_ERROR(getLogger(), "No kinematics solvers specified. Unable to construct a "
72 "PoseModelStateSpace");
73 }
74 else
75 {
76 std::sort(poses_.begin(), poses_.end());
77 }
78 setName(getName() + "_" + PARAMETERIZATION_TYPE);
79}
80
82
83double PoseModelStateSpace::distance(const ompl::base::State* state1, const ompl::base::State* state2) const
84{
85 return ModelBasedStateSpace::distance(state1, state2);
86}
87
89{
90 double total = 0.0;
91 for (const auto& pose : poses_)
92 total += pose.state_space_->getMaximumExtent();
93 return total;
94}
95
96ompl::base::State* PoseModelStateSpace::allocState() const
97{
98 auto* state = new StateType();
99 state->values =
100 new double[variable_count_]; // need to allocate this here since ModelBasedStateSpace::allocState() is not called
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>();
104 return state;
105}
106
107void PoseModelStateSpace::freeState(ompl::base::State* state) const
108{
109 for (std::size_t i = 0; i < poses_.size(); ++i)
110 poses_[i].state_space_->freeState(state->as<StateType>()->poses[i]);
111 delete[] state->as<StateType>()->poses;
113}
114
115void PoseModelStateSpace::copyState(ompl::base::State* destination, const ompl::base::State* source) const
116{
117 // copy the state data
118 ModelBasedStateSpace::copyState(destination, source);
119
120 for (std::size_t i = 0; i < poses_.size(); ++i)
121 poses_[i].state_space_->copyState(destination->as<StateType>()->poses[i], source->as<StateType>()->poses[i]);
122
123 // compute additional stuff if needed
124 computeStateK(destination);
125}
126
128{
129 ModelBasedStateSpace::sanityChecks(std::numeric_limits<double>::epsilon(), std::numeric_limits<double>::epsilon(),
130 ~ompl::base::StateSpace::STATESPACE_TRIANGLE_INEQUALITY);
131}
132
133void PoseModelStateSpace::interpolate(const ompl::base::State* from, const ompl::base::State* to, const double t,
134 ompl::base::State* state) const
135{
136 // we want to interpolate in Cartesian space to avoid rejection of path constraints
137
138 // interpolate in joint space to find a suitable seed for IK
139 ModelBasedStateSpace::interpolate(from, to, t, state);
140 double d_joint = ModelBasedStateSpace::distance(from, state);
141
142 // interpolate SE3 components
143 for (std::size_t i = 0; i < poses_.size(); ++i)
144 {
145 poses_[i].state_space_->interpolate(from->as<StateType>()->poses[i], to->as<StateType>()->poses[i], t,
146 state->as<StateType>()->poses[i]);
147 }
148
149 // the call above may reset all flags for state; but we know the pose we want flag should be set
150 state->as<StateType>()->setPoseComputed(true);
151
152 // compute IK for interpolated Cartesian state
153 if (computeStateIK(state))
154 {
155 double d_cart = ModelBasedStateSpace::distance(from, state);
156
157 // reject if Cartesian interpolation yields much larger distance than joint interpolation
158 if (d_cart > jump_factor_ * d_joint)
159 state->as<StateType>()->markInvalid();
160 }
161}
162
163void PoseModelStateSpace::setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
164{
165 ModelBasedStateSpace::setPlanningVolume(minX, maxX, minY, maxY, minZ, maxZ);
166 ompl::base::RealVectorBounds b(3);
167 b.low[0] = minX;
168 b.low[1] = minY;
169 b.low[2] = minZ;
170 b.high[0] = maxX;
171 b.high[1] = maxY;
172 b.high[2] = maxZ;
173 for (auto& pose : poses_)
174 pose.state_space_->as<ompl::base::SE3StateSpace>()->setBounds(b);
175}
176
177PoseModelStateSpace::PoseComponent::PoseComponent(const moveit::core::JointModelGroup* subgroup,
179 : subgroup_(subgroup), kinematics_solver_(k.allocator_(subgroup)), bijection_(k.bijection_)
180{
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);
186}
187
188bool PoseModelStateSpace::PoseComponent::computeStateFK(StateType* full_state, unsigned int idx) const
189{
190 // read the values from the joint state, in the order expected by the kinematics solver
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]];
194
195 // compute forward kinematics for the link of interest
196 std::vector<geometry_msgs::msg::Pose> poses;
197 if (!kinematics_solver_->getPositionFK(fk_link_, values, poses))
198 return false;
199
200 // copy the resulting data to the desired location in the state
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;
208
209 return true;
210}
211
212bool PoseModelStateSpace::PoseComponent::computeStateIK(StateType* full_state, unsigned int idx) const
213{
214 // read the values from the joint state, in the order expected by the kinematics solver; use these as the seed
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]];
218
219 /*
220 std::cout << "seed: ";
221 for (std::size_t i = 0 ; i < seed_values.size() ; ++i)
222 std::cout << seed_values[i] << " ";
223 std::cout << '\n';
224 */
225
226 // construct the pose
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;
237
238 // run IK
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))
242 {
243 if (err_code.val != moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT ||
244 !kinematics_solver_->searchPositionIK(pose, seed_values, kinematics_solver_->getDefaultTimeout() * 2.0,
245 solution, err_code))
246 return false;
247 }
248
249 for (std::size_t i = 0; i < bijection_.size(); ++i)
250 full_state->values[bijection_[i]] = solution[i];
251
252 return true;
253}
254
255bool PoseModelStateSpace::computeStateFK(ompl::base::State* state) const
256{
257 if (state->as<StateType>()->poseComputed())
258 return true;
259 for (std::size_t i = 0; i < poses_.size(); ++i)
260 {
261 if (!poses_[i].computeStateFK(state->as<StateType>(), i))
262 {
263 state->as<StateType>()->markInvalid();
264 return false;
265 }
266 }
267 state->as<StateType>()->setPoseComputed(true);
268 return true;
269}
270
271bool PoseModelStateSpace::computeStateIK(ompl::base::State* state) const
272{
273 if (state->as<StateType>()->jointsComputed())
274 return true;
275 for (std::size_t i = 0; i < poses_.size(); ++i)
276 {
277 if (!poses_[i].computeStateIK(state->as<StateType>(), i))
278 {
279 state->as<StateType>()->markInvalid();
280 return false;
281 }
282 }
283 state->as<StateType>()->setJointsComputed(true);
284 return true;
285}
286
287bool PoseModelStateSpace::computeStateK(ompl::base::State* state) const
288{
289 if (state->as<StateType>()->jointsComputed() && !state->as<StateType>()->poseComputed())
290 return computeStateFK(state);
291 if (!state->as<StateType>()->jointsComputed() && state->as<StateType>()->poseComputed())
292 return computeStateIK(state);
293 if (state->as<StateType>()->jointsComputed() && state->as<StateType>()->poseComputed())
294 return true;
295 state->as<StateType>()->markInvalid();
296 return false;
297}
298
299ompl::base::StateSamplerPtr PoseModelStateSpace::allocDefaultStateSampler() const
300{
301 class PoseModelStateSampler : public ompl::base::StateSampler
302 {
303 public:
304 PoseModelStateSampler(const ompl::base::StateSpace* space, ompl::base::StateSamplerPtr sampler)
305 : ompl::base::StateSampler(space), sampler_(std::move(sampler))
306 {
307 }
308
309 void sampleUniform(ompl::base::State* state) override
310 {
311 sampler_->sampleUniform(state);
312 afterStateSample(state);
313 }
314
315 void sampleUniformNear(ompl::base::State* state, const ompl::base::State* near, const double distance) override
316 {
317 sampler_->sampleUniformNear(state, near, distance);
318 afterStateSample(state);
319 }
320
321 void sampleGaussian(ompl::base::State* state, const ompl::base::State* mean, const double stdDev) override
322 {
323 sampler_->sampleGaussian(state, mean, stdDev);
324 afterStateSample(state);
325 }
326
327 protected:
328 void afterStateSample(ompl::base::State* sample) const
329 {
330 sample->as<StateType>()->setJointsComputed(true);
331 sample->as<StateType>()->setPoseComputed(false);
332 space_->as<PoseModelStateSpace>()->computeStateFK(sample);
333 }
334
335 ompl::base::StateSamplerPtr sampler_;
336 };
337
338 return ompl::base::StateSamplerPtr(static_cast<ompl::base::StateSampler*>(
339 new PoseModelStateSampler(this, ModelBasedStateSpace::allocDefaultStateSampler())));
340}
341
342void PoseModelStateSpace::copyToOMPLState(ompl::base::State* state, const moveit::core::RobotState& rstate) const
343{
345 state->as<StateType>()->setJointsComputed(true);
346 state->as<StateType>()->setPoseComputed(false);
347 computeStateFK(state);
348}
349
350} // namespace ompl_interface
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.
Definition robot_state.h:90
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.
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
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.
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
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(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
The MoveIt interface to OMPL.
const moveit::core::JointModelGroup * joint_model_group_