moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
default_constraint_samplers.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, 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 <rclcpp/logger.hpp>
39#include <rclcpp/logging.hpp>
40#include <cassert>
41#include <functional>
43
44namespace constraint_samplers
45{
46namespace
47{
48rclcpp::Logger getLogger()
49{
50 return moveit::getLogger("moveit.core.default_constraint_samplers");
51}
52} // namespace
53
54bool JointConstraintSampler::configure(const moveit_msgs::msg::Constraints& constr)
55{
56 // construct the constraints
57 std::vector<kinematic_constraints::JointConstraint> jc;
58 for (const moveit_msgs::msg::JointConstraint& joint_constraint : constr.joint_constraints)
59 {
61 if (j.configure(joint_constraint))
62 jc.push_back(j);
63 }
64
65 return jc.empty() ? false : configure(jc);
66}
67
68bool JointConstraintSampler::configure(const std::vector<kinematic_constraints::JointConstraint>& jc)
69{
70 clear();
71
72 if (!jmg_)
73 {
74 RCLCPP_ERROR(getLogger(), "nullptr group specified for constraint sampler");
75 return false;
76 }
77
78 // find and keep the constraints that operate on the group we sample
79 // also keep bounds for joints as convenient
80 std::map<std::string, JointInfo> bound_data;
81 bool some_valid_constraint = false;
82 for (const kinematic_constraints::JointConstraint& joint_constraint : jc)
83 {
84 if (!joint_constraint.enabled())
85 continue;
86
87 const moveit::core::JointModel* jm = joint_constraint.getJointModel();
88 if (!jmg_->hasJointModel(jm->getName()))
89 continue;
90
91 some_valid_constraint = true;
92
93 const moveit::core::VariableBounds& joint_bounds = jm->getVariableBounds(joint_constraint.getJointVariableName());
94 JointInfo ji;
95 std::map<std::string, JointInfo>::iterator it = bound_data.find(joint_constraint.getJointVariableName());
96 if (it != bound_data.end())
97 {
98 ji = it->second;
99 }
100 else
101 {
102 ji.index_ = jmg_->getVariableGroupIndex(joint_constraint.getJointVariableName());
103 }
105 std::max(joint_bounds.min_position_,
106 joint_constraint.getDesiredJointPosition() - joint_constraint.getJointToleranceBelow()),
107 std::min(joint_bounds.max_position_,
108 joint_constraint.getDesiredJointPosition() + joint_constraint.getJointToleranceAbove()));
109
110 RCLCPP_DEBUG(getLogger(), "Bounds for %s JointConstraint are %g %g",
111 joint_constraint.getJointVariableName().c_str(), ji.min_bound_, ji.max_bound_);
112
113 if (ji.min_bound_ > ji.max_bound_ + std::numeric_limits<double>::epsilon())
114 {
115 std::stringstream cs;
116 joint_constraint.print(cs);
117 RCLCPP_ERROR(getLogger(),
118 "The constraints for joint '%s' are such that "
119 "there are no possible values for the joint: min_bound: %g, max_bound: %g. Failing.\n",
120 jm->getName().c_str(), ji.min_bound_, ji.max_bound_);
121 clear();
122 return false;
123 }
124 bound_data[joint_constraint.getJointVariableName()] = ji;
125 }
126
127 if (!some_valid_constraint)
128 {
129 RCLCPP_WARN(getLogger(), "No valid joint constraints");
130 return false;
131 }
132
133 for (std::pair<const std::string, JointInfo>& it : bound_data)
134 bounds_.push_back(it.second);
135
136 // get a separate list of joints that are not bounded; we will sample these randomly
137 const std::vector<const moveit::core::JointModel*>& joints = jmg_->getJointModels();
138 for (const moveit::core::JointModel* joint : joints)
139 {
140 if (bound_data.find(joint->getName()) == bound_data.end() && joint->getVariableCount() > 0 &&
141 joint->getMimic() == nullptr)
142 {
143 // check if all the vars of the joint are found in bound_data instead
144 const std::vector<std::string>& vars = joint->getVariableNames();
145 if (vars.size() > 1)
146 {
147 bool all_found = true;
148 for (const std::string& var : vars)
149 {
150 if (bound_data.find(var) == bound_data.end())
151 {
152 all_found = false;
153 break;
154 }
155 }
156 if (all_found)
157 continue;
158 }
159 unbounded_.push_back(joint);
160 // Get the first variable name of this joint and find its index position in the planning group
161 uindex_.push_back(jmg_->getVariableGroupIndex(vars[0]));
162 }
163 }
164 values_.resize(jmg_->getVariableCount());
165 is_valid_ = true;
166 return true;
167}
168
170 const moveit::core::RobotState& /* reference_state */,
171 unsigned int /* max_attempts */)
172{
173 if (!is_valid_)
174 {
175 RCLCPP_WARN(getLogger(), "JointConstraintSampler not configured, won't sample");
176 return false;
177 }
178
179 // sample the unbounded joints first (in case some joint variables are bounded)
180 std::vector<double> v;
181 for (std::size_t i = 0; i < unbounded_.size(); ++i)
182 {
183 v.resize(unbounded_[i]->getVariableCount());
184 unbounded_[i]->getVariableRandomPositions(random_number_generator_, &v[0]);
185 for (std::size_t j = 0; j < v.size(); ++j)
186 values_[uindex_[i] + j] = v[j];
187 }
188
189 // enforce the constraints for the constrained components (could be all of them)
190 for (const JointInfo& bound : bounds_)
191 values_[bound.index_] = random_number_generator_.uniformReal(bound.min_bound_, bound.max_bound_);
192
194
195 // we are always successful
196 return true;
197}
198
200{
202 bounds_.clear();
203 unbounded_.clear();
204 uindex_.clear();
205 values_.clear();
206}
207
211
213 : position_constraint_(std::make_shared<kinematic_constraints::PositionConstraint>(pc))
214{
215}
216
218 : orientation_constraint_(std::make_shared<kinematic_constraints::OrientationConstraint>(oc))
219{
220}
221
224 : position_constraint_(std::make_shared<kinematic_constraints::PositionConstraint>(pc))
225 , orientation_constraint_(std::make_shared<kinematic_constraints::OrientationConstraint>(oc))
226{
227}
228
229IKSamplingPose::IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc) : position_constraint_(pc)
230{
231}
232
233IKSamplingPose::IKSamplingPose(const kinematic_constraints::OrientationConstraintPtr& oc) : orientation_constraint_(oc)
234{
235}
236
237IKSamplingPose::IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc,
238 const kinematic_constraints::OrientationConstraintPtr& oc)
239 : position_constraint_(pc), orientation_constraint_(oc)
240{
241}
242
244{
246 kb_.reset();
247 ik_frame_ = "";
248 transform_ik_ = false;
249 eef_to_ik_tip_transform_ = Eigen::Isometry3d::Identity();
251}
252
254{
255 clear();
257 return false;
258 if ((!sp.orientation_constraint_ && !sp.position_constraint_->enabled()) ||
259 (!sp.position_constraint_ && !sp.orientation_constraint_->enabled()) ||
261 !sp.orientation_constraint_->enabled()))
262 {
263 RCLCPP_WARN(getLogger(), "No enabled constraints in sampling pose");
264 return false;
265 }
266
267 sampling_pose_ = sp;
270 {
271 if (sampling_pose_.position_constraint_->getLinkModel()->getName() !=
272 sampling_pose_.orientation_constraint_->getLinkModel()->getName())
273 {
274 RCLCPP_ERROR(getLogger(), "Position and orientation constraints need to be specified for the same link "
275 "in order to use IK-based sampling");
276 return false;
277 }
278 }
279
281 frame_depends_.push_back(sampling_pose_.position_constraint_->getReferenceFrame());
283 frame_depends_.push_back(sampling_pose_.orientation_constraint_->getReferenceFrame());
285 if (!kb_)
286 {
287 RCLCPP_WARN(getLogger(), "No solver instance in setup");
288 is_valid_ = false;
289 return false;
290 }
292 return is_valid_;
293}
294
295bool IKConstraintSampler::configure(const moveit_msgs::msg::Constraints& constr)
296{
297 for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
298 {
299 for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
300 {
301 if (constr.position_constraints[p].link_name == constr.orientation_constraints[o].link_name)
302 {
303 kinematic_constraints::PositionConstraintPtr pc(
305 kinematic_constraints::OrientationConstraintPtr oc(
307 if (pc->configure(constr.position_constraints[p], scene_->getTransforms()) &&
308 oc->configure(constr.orientation_constraints[o], scene_->getTransforms()))
309 return configure(IKSamplingPose(pc, oc));
310 }
311 }
312 }
313
314 for (const moveit_msgs::msg::PositionConstraint& position_constraint : constr.position_constraints)
315 {
316 kinematic_constraints::PositionConstraintPtr pc(
318 if (pc->configure(position_constraint, scene_->getTransforms()))
319 return configure(IKSamplingPose(pc));
320 }
321
322 for (const moveit_msgs::msg::OrientationConstraint& orientation_constraint : constr.orientation_constraints)
323 {
324 kinematic_constraints::OrientationConstraintPtr oc(
326 if (oc->configure(orientation_constraint, scene_->getTransforms()))
327 return configure(IKSamplingPose(oc));
328 }
329 return false;
330}
331
333{
334 double v = 1.0;
336 {
337 const std::vector<bodies::BodyPtr>& constraint_regions =
338 sampling_pose_.position_constraint_->getConstraintRegions();
339 double vol = 0;
340 for (const bodies::BodyPtr& constraint_region : constraint_regions)
341 vol += constraint_region->computeVolume();
342 if (!constraint_regions.empty())
343 v *= vol;
344 }
345
347 {
348 v *= sampling_pose_.orientation_constraint_->getXAxisTolerance() *
349 sampling_pose_.orientation_constraint_->getYAxisTolerance() *
350 sampling_pose_.orientation_constraint_->getZAxisTolerance();
351 }
352 return v;
353}
354
355const std::string& IKConstraintSampler::getLinkName() const
356{
358 return sampling_pose_.orientation_constraint_->getLinkModel()->getName();
359 return sampling_pose_.position_constraint_->getLinkModel()->getName();
360}
361
363{
364 if (!kb_)
365 {
366 RCLCPP_ERROR(getLogger(), "No IK solver");
367 return false;
368 }
369
370 // check if we need to transform the request into the coordinate frame expected by IK
371 ik_frame_ = kb_->getBaseFrame();
373 if (!ik_frame_.empty() && ik_frame_[0] == '/')
374 ik_frame_.erase(ik_frame_.begin());
375 if (transform_ik_)
376 {
378 {
379 RCLCPP_ERROR(getLogger(),
380 "The IK solver expects requests in frame '%s' but this frame is not known to the sampler. "
381 "Ignoring transformation (IK may fail)",
382 ik_frame_.c_str());
383 transform_ik_ = false;
384 }
385 }
386
387 // check if IK is performed for the desired link
388 bool wrong_link = false;
390 {
392 if (!moveit::core::Transforms::sameFrame(kb_->getTipFrame(), lm->getName()))
393 {
394 wrong_link = true;
396 for (const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
397 {
398 if (moveit::core::Transforms::sameFrame(fixed_link.first->getName(), kb_->getTipFrame()))
399 {
400 eef_to_ik_tip_transform_ = fixed_link.second; // valid isometry by contract
402 wrong_link = false;
403 break;
404 }
405 }
406 }
407 }
408
409 if (!wrong_link && sampling_pose_.orientation_constraint_)
410 {
412 if (!moveit::core::Transforms::sameFrame(kb_->getTipFrame(), lm->getName()))
413 {
414 wrong_link = true;
416 for (const std::pair<const moveit::core::LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
417 {
418 if (moveit::core::Transforms::sameFrame(fixed_link.first->getName(), kb_->getTipFrame()))
419 {
420 eef_to_ik_tip_transform_ = fixed_link.second; // valid isometry by contract
422 wrong_link = false;
423 break;
424 }
425 }
426 }
427 }
428
429 if (wrong_link)
430 {
431 RCLCPP_ERROR(getLogger(), "IK cannot be performed for link '%s'. The solver can report IK solutions for link '%s'.",
433 sampling_pose_.position_constraint_->getLinkModel()->getName().c_str() :
434 sampling_pose_.orientation_constraint_->getLinkModel()->getName().c_str(),
435 kb_->getTipFrame().c_str());
436 return false;
437 }
438 return true;
439}
440
441bool IKConstraintSampler::samplePose(Eigen::Vector3d& pos, Eigen::Quaterniond& quat, const moveit::core::RobotState& ks,
442 unsigned int max_attempts)
443{
444 if (ks.dirtyLinkTransforms())
445 {
446 // samplePose below requires accurate transforms
447 RCLCPP_ERROR(getLogger(), "IKConstraintSampler received dirty robot state, but valid transforms are required. "
448 "Failing.");
449 return false;
450 }
451
453 {
454 const std::vector<bodies::BodyPtr>& b = sampling_pose_.position_constraint_->getConstraintRegions();
455 if (!b.empty())
456 {
457 bool found = false;
458 std::size_t k = random_number_generator_.uniformInteger(0, b.size() - 1);
459 for (std::size_t i = 0; i < b.size(); ++i)
460 {
461 if (b[(i + k) % b.size()]->samplePointInside(random_number_generator_, max_attempts, pos))
462 {
463 found = true;
464 break;
465 }
466 }
467 if (!found)
468 {
469 RCLCPP_ERROR(getLogger(), "Unable to sample a point inside the constraint region");
470 return false;
471 }
472 }
473 else
474 {
475 RCLCPP_ERROR(getLogger(), "Unable to sample a point inside the constraint region. "
476 "Constraint region is empty when it should not be.");
477 return false;
478 }
479
480 // if this constraint is with respect a mobile frame, we need to convert this rotation to the root frame of the
481 // model
482 if (sampling_pose_.position_constraint_->mobileReferenceFrame())
483 pos = ks.getFrameTransform(sampling_pose_.position_constraint_->getReferenceFrame()) * pos;
484 }
485 else
486 {
487 // do FK for rand state
488 moveit::core::RobotState temp_state(ks);
489 temp_state.setToRandomPositions(jmg_);
490 pos = temp_state.getGlobalLinkTransform(sampling_pose_.orientation_constraint_->getLinkModel()).translation();
491 }
492
494 {
495 // sample a rotation matrix within the allowed bounds
496 double angle_x =
497 2.0 * (random_number_generator_.uniform01() - 0.5) *
498 (sampling_pose_.orientation_constraint_->getXAxisTolerance() - std::numeric_limits<double>::epsilon());
499 double angle_y =
500 2.0 * (random_number_generator_.uniform01() - 0.5) *
501 (sampling_pose_.orientation_constraint_->getYAxisTolerance() - std::numeric_limits<double>::epsilon());
502 double angle_z =
503 2.0 * (random_number_generator_.uniform01() - 0.5) *
504 (sampling_pose_.orientation_constraint_->getZAxisTolerance() - std::numeric_limits<double>::epsilon());
505
506 Eigen::Isometry3d diff;
507 if (sampling_pose_.orientation_constraint_->getParameterizationType() ==
508 moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES)
509 {
510 diff = Eigen::Isometry3d(Eigen::AngleAxisd(angle_x, Eigen::Vector3d::UnitX()) *
511 Eigen::AngleAxisd(angle_y, Eigen::Vector3d::UnitY()) *
512 Eigen::AngleAxisd(angle_z, Eigen::Vector3d::UnitZ()));
513 }
514 else if (sampling_pose_.orientation_constraint_->getParameterizationType() ==
515 moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR)
516 {
517 Eigen::Vector3d rotation_vector(angle_x, angle_y, angle_z);
518 diff = Eigen::Isometry3d(Eigen::AngleAxisd(rotation_vector.norm(), rotation_vector.normalized()));
519 }
520 else
521 {
522 /* The parameterization type should be validated in configure, so this should never happen. */
523 RCLCPP_ERROR(getLogger(), "The parameterization type for the orientation constraints is invalid.");
524 }
525 // diff is isometry by construction
526 // getDesiredRotationMatrix() returns a valid rotation matrix by contract
527 // reqr has thus to be a valid isometry
528 Eigen::Isometry3d reqr(sampling_pose_.orientation_constraint_->getDesiredRotationMatrix() * diff.linear());
529 quat = Eigen::Quaterniond(reqr.linear()); // reqr is isometry, so quat has to be normalized
530
531 // if this constraint is with respect a mobile frame, we need to convert this rotation to the root frame of the
532 // model
533 if (sampling_pose_.orientation_constraint_->mobileReferenceFrame())
534 {
535 // getFrameTransform() returns a valid isometry by contract
536 const Eigen::Isometry3d& t = ks.getFrameTransform(sampling_pose_.orientation_constraint_->getReferenceFrame());
537 // rt is isometry by construction
538 Eigen::Isometry3d rt(t.linear() * quat);
539 quat = Eigen::Quaterniond(rt.linear()); // rt is isometry, so quat has to be normalized
540 }
541 }
542 else
543 {
544 // sample a random orientation
545 double q[4];
546 random_number_generator_.quaternion(q);
547 quat = Eigen::Quaterniond(q[3], q[0], q[1], q[2]); // quat is normalized by contract
548 }
549
550 // if there is an offset, we need to undo the induced rotation in the sampled transform origin (point)
552 {
553 // the rotation matrix that corresponds to the desired orientation
554 pos = pos - quat * sampling_pose_.position_constraint_->getLinkOffset();
555 }
556
557 return true;
558}
559
560namespace
561{
562void samplingIkCallbackFnAdapter(moveit::core::RobotState* state, const moveit::core::JointModelGroup* jmg,
564 const std::vector<double>& ik_sol, moveit_msgs::msg::MoveItErrorCodes& error_code)
565{
566 const std::vector<size_t>& bij = jmg->getKinematicsSolverJointBijection();
567 std::vector<double> solution(bij.size());
568 for (std::size_t i = 0; i < bij.size(); ++i)
569 solution[i] = ik_sol[bij[i]];
570 if (constraint(state, jmg, &solution[0]))
571 {
572 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
573 }
574 else
575 {
576 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
577 }
578}
579} // namespace
580
582 unsigned int max_attempts)
583{
584 return sampleHelper(state, reference_state, max_attempts);
585}
586
588 unsigned int max_attempts)
589{
590 if (!is_valid_)
591 {
592 RCLCPP_WARN(getLogger(), "IKConstraintSampler not configured, won't sample");
593 return false;
594 }
595
596 kinematics::KinematicsBase::IKCallbackFn adapted_ik_validity_callback;
598 {
599 adapted_ik_validity_callback = [this, state_ptr = &state](const geometry_msgs::msg::Pose&,
600 const std::vector<double>& joints,
601 moveit_msgs::msg::MoveItErrorCodes& error_code) {
602 return samplingIkCallbackFnAdapter(state_ptr, jmg_, group_state_validity_callback_, joints, error_code);
603 };
604 }
605
606 for (unsigned int a = 0; a < max_attempts; ++a)
607 {
608 // sample a point in the constraint region
609 Eigen::Vector3d point;
610 Eigen::Quaterniond quat; // quat is normalized by contract
611 if (!samplePose(point, quat, reference_state, max_attempts))
612 {
613 if (verbose_)
614 RCLCPP_INFO(getLogger(), "IK constraint sampler was unable to produce a pose to run IK for");
615 return false;
616 }
617
618 // we now have the transform we wish to perform IK for, in the planning frame
619 if (transform_ik_)
620 {
621 // we need to convert this transform to the frame expected by the IK solver
622 // both the planning frame and the frame for the IK are assumed to be robot links
623 Eigen::Isometry3d ikq(Eigen::Translation3d(point) * quat); // valid isometry by construction
624 // getFrameTransform() returns a valid isometry by contract
625 ikq = reference_state.getFrameTransform(ik_frame_).inverse() * ikq; // valid isometry * valid isometry
626 point = ikq.translation();
627 quat = Eigen::Quaterniond(ikq.linear()); // ikq is isometry, so quat is normalized
628 }
629
631 {
632 // After sampling the pose needs to be transformed to the ik chain tip
633 Eigen::Isometry3d ikq(Eigen::Translation3d(point) * quat); // valid isometry by construction
634 ikq = ikq * eef_to_ik_tip_transform_; // eef_to_ik_tip_transform_ is valid isometry (checked in loadIKSolver())
635 point = ikq.translation();
636 quat = Eigen::Quaterniond(ikq.linear()); // ikq is isometry, so quat is normalized
637 }
638
639 geometry_msgs::msg::Pose ik_query;
640 ik_query.position.x = point.x();
641 ik_query.position.y = point.y();
642 ik_query.position.z = point.z();
643 ik_query.orientation.x = quat.x();
644 ik_query.orientation.y = quat.y();
645 ik_query.orientation.z = quat.z();
646 ik_query.orientation.w = quat.w();
647
648 if (callIK(ik_query, adapted_ik_validity_callback, ik_timeout_, state, a == 0))
649 return true;
650 }
651 return false;
652}
653
662
663bool IKConstraintSampler::callIK(const geometry_msgs::msg::Pose& ik_query,
664 const kinematics::KinematicsBase::IKCallbackFn& adapted_ik_validity_callback,
665 double timeout, moveit::core::RobotState& state, bool use_as_seed)
666{
667 const std::vector<size_t>& ik_joint_bijection = jmg_->getKinematicsSolverJointBijection();
668 std::vector<double> seed(ik_joint_bijection.size(), 0.0);
669 std::vector<double> vals;
670
671 if (use_as_seed)
672 {
673 state.copyJointGroupPositions(jmg_, vals);
674 }
675 else
676 {
677 // sample a seed value
679 }
680
681 assert(vals.size() == ik_joint_bijection.size());
682 for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
683 seed[i] = vals[ik_joint_bijection[i]];
684
685 std::vector<double> ik_sol;
686 moveit_msgs::msg::MoveItErrorCodes error;
687
688 if (adapted_ik_validity_callback ?
689 kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, adapted_ik_validity_callback, error) :
690 kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, error))
691 {
692 assert(ik_sol.size() == ik_joint_bijection.size());
693 std::vector<double> solution(ik_joint_bijection.size());
694 for (std::size_t i = 0; i < ik_joint_bijection.size(); ++i)
695 solution[ik_joint_bijection[i]] = ik_sol[i];
696 state.setJointGroupPositions(jmg_, solution);
697
698 return validate(state);
699 }
700 else
701 {
702 if (error.val != moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION &&
703 error.val != moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE &&
704 error.val != moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT)
705 {
706 RCLCPP_ERROR(getLogger(), "IK solver failed with error %d", error.val);
707 }
708 else if (verbose_)
709 {
710 RCLCPP_INFO(getLogger(), "IK failed");
711 }
712 }
713 return false;
714}
715
716} // end of namespace constraint_samplers
bool is_valid_
Holds the value for validity.
std::vector< std::string > frame_depends_
Holds the set of frames that must exist in the reference state to allow samples to be drawn.
const moveit::core::JointModelGroup *const jmg_
Holds the joint model group associated with this constraint.
virtual void clear()
Clears all data from the constraint.
moveit::core::GroupStateValidityCallbackFn group_state_validity_callback_
Holds the callback for state validity.
bool verbose_
True if verbosity is on.
planning_scene::PlanningSceneConstPtr scene_
Holds the planning scene.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures the IK constraint given a constraints message.
double ik_timeout_
Holds the timeout associated with IK.
bool loadIKSolver()
Performs checks and sets various internal values associated with the IK solver.
const std::string & getLinkName() const
Gets the link name associated with this sampler.
bool validate(moveit::core::RobotState &state) const
IKSamplingPose sampling_pose_
Holder for the pose used for sampling.
bool callIK(const geometry_msgs::msg::Pose &ik_query, const kinematics::KinematicsBase::IKCallbackFn &adapted_ik_validity_callback, double timeout, moveit::core::RobotState &state, bool use_as_seed)
Actually calls IK on the given pose, generating a random seed state.
double getSamplingVolume() const
Gets the volume associated with the position and orientation constraints.
Eigen::Isometry3d eef_to_ik_tip_transform_
Holds the transformation from end effector to IK tip frame.
bool need_eef_to_ik_tip_transform_
True if the tip frame of the inverse kinematic is different than the frame of the end effector.
kinematics::KinematicsBaseConstPtr kb_
Holds the kinematics solver.
void clear() override
Clears all data from the constraint.
bool sampleHelper(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts)
std::string ik_frame_
Holds the base from of the IK solver.
random_numbers::RandomNumberGenerator random_number_generator_
Random generator used by the sampler.
bool transform_ik_
True if the frame associated with the kinematic model is different than the base frame of the IK solv...
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
Produces an IK sample.
bool samplePose(Eigen::Vector3d &pos, Eigen::Quaterniond &quat, const moveit::core::RobotState &ks, unsigned int max_attempts)
Returns a pose that falls within the constraint regions.
std::vector< unsigned int > uindex_
The index of the unbounded joints in the joint state vector.
void clear() override
Clears all data from the constraint.
random_numbers::RandomNumberGenerator random_number_generator_
Random number generator used to sample.
std::vector< const moveit::core::JointModel * > unbounded_
The joints that are not bounded except by joint limits.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures a joint constraint given a Constraints message.
std::vector< JointInfo > bounds_
The bounds for any joint with bounds that are more restrictive than the joint limits.
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &ks, unsigned int max_attempts) override
Samples given the constraints, populating state. This function allows the parameter max_attempts to b...
std::vector< double > values_
Values associated with this group to avoid continuously reallocating.
Class for handling single DOF joint constraints.
bool configure(const moveit_msgs::msg::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::msg::JointConstraint.
Class for constraints on the orientation of a link.
Class for constraints on the XYZ position of a link.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
double getDefaultIKTimeout() const
Get the default IK timeout.
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
const std::vector< size_t > & getKinematicsSolverJointBijection() const
Return the mapping between the order of the joints in this group and the order of the joints in the k...
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const std::string & getName() const
Get the name of the joint.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
const std::string & getName() const
The name of this link.
Definition link_model.h:86
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
Definition link_model.h:199
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState)....
Definition robot_model.h:94
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool dirtyLinkTransforms() const
void update(bool force=false)
Update all transforms.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
Representation and evaluation of kinematic constraints.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition robot_state.h:70
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
Definition link_model.h:68
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
A structure for potentially holding a position constraint and an orientation constraint for use durin...
kinematic_constraints::PositionConstraintPtr position_constraint_
Holds the position constraint for sampling.
kinematic_constraints::OrientationConstraintPtr orientation_constraint_
Holds the orientation constraint for sampling.
An internal structure used for maintaining constraints on a particular joint.
void potentiallyAdjustMinMaxBounds(double min, double max)
Function that adjusts the joints only if they are more restrictive. This means that the min limit is ...