38 #include <geometric_shapes/check_isometry.h>
39 #include <geometric_shapes/shape_operations.h>
43 #include <rclcpp/clock.hpp>
44 #include <rclcpp/logger.hpp>
45 #include <rclcpp/logging.hpp>
46 #include <rclcpp/time.hpp>
47 #include <tf2_eigen/tf2_eigen.hpp>
58 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_robot_state.robot_state");
61 : robot_model_(robot_model)
62 , has_velocity_(false)
63 , has_acceleration_(false)
65 , dirty_link_transforms_(nullptr)
66 , dirty_collision_body_transforms_(nullptr)
69 if (robot_model ==
nullptr)
71 throw std::invalid_argument(
"RobotState cannot be constructed with nullptr RobotModelConstPtr");
74 dirty_link_transforms_ = robot_model_->getRootJoint();
81 robot_model_ = other.robot_model_;
94 void RobotState::allocMemory()
96 static_assert((
sizeof(Eigen::Isometry3d) / EIGEN_MAX_ALIGN_BYTES) * EIGEN_MAX_ALIGN_BYTES ==
sizeof(Eigen::Isometry3d),
97 "sizeof(Eigen::Isometry3d) should be a multiple of EIGEN_MAX_ALIGN_BYTES");
99 constexpr
unsigned int extra_alignment_bytes = EIGEN_MAX_ALIGN_BYTES - 1;
101 const int nr_doubles_for_dirty_joint_transforms =
102 1 + robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
104 sizeof(Eigen::Isometry3d) * (robot_model_->getJointModelCount() + robot_model_->getLinkModelCount() +
105 robot_model_->getLinkGeometryCount()) +
106 sizeof(
double) * (robot_model_->getVariableCount() * 3 + nr_doubles_for_dirty_joint_transforms) +
107 extra_alignment_bytes;
108 memory_ = malloc(bytes);
113 variable_joint_transforms_ =
reinterpret_cast<Eigen::Isometry3d*
>(
114 (
reinterpret_cast<uintptr_t
>(memory_) + extra_alignment_bytes) & ~static_cast<uintptr_t>(extra_alignment_bytes));
115 global_link_transforms_ = variable_joint_transforms_ + robot_model_->getJointModelCount();
116 global_collision_body_transforms_ = global_link_transforms_ + robot_model_->getLinkModelCount();
117 dirty_joint_transforms_ =
118 reinterpret_cast<unsigned char*
>(global_collision_body_transforms_ + robot_model_->getLinkGeometryCount());
119 position_ =
reinterpret_cast<double*
>(dirty_joint_transforms_) + nr_doubles_for_dirty_joint_transforms;
120 velocity_ = position_ + robot_model_->getVariableCount();
122 effort_ = acceleration_ = velocity_ + robot_model_->getVariableCount();
125 void RobotState::initTransforms()
128 const int nr_doubles_for_dirty_joint_transforms =
129 1 + robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
130 memset(dirty_joint_transforms_, 1,
sizeof(
double) * nr_doubles_for_dirty_joint_transforms);
133 for (
size_t i = 0, end = robot_model_->getJointModelCount() + robot_model_->getLinkModelCount() +
134 robot_model_->getLinkGeometryCount();
136 variable_joint_transforms_[i].makeAffine();
146 void RobotState::copyFrom(
const RobotState& other)
148 has_velocity_ = other.has_velocity_;
149 has_acceleration_ = other.has_acceleration_;
150 has_effort_ = other.has_effort_;
152 dirty_collision_body_transforms_ = other.dirty_collision_body_transforms_;
153 dirty_link_transforms_ = other.dirty_link_transforms_;
155 if (dirty_link_transforms_ == robot_model_->getRootJoint())
158 memcpy(position_, other.position_,
159 robot_model_->getVariableCount() *
sizeof(
double) *
160 (1 + (has_velocity_ ? 1 : 0) + ((has_acceleration_ || has_effort_) ? 1 : 0)));
167 const int nr_doubles_for_dirty_joint_transforms =
168 1 + robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
170 sizeof(Eigen::Isometry3d) * (robot_model_->getJointModelCount() + robot_model_->getLinkModelCount() +
171 robot_model_->getLinkGeometryCount()) +
173 (robot_model_->getVariableCount() * (1 + ((has_velocity_ || has_acceleration_ || has_effort_) ? 1 : 0) +
174 ((has_acceleration_ || has_effort_) ? 1 : 0)) +
175 nr_doubles_for_dirty_joint_transforms);
176 memcpy(
static_cast<void*
>(variable_joint_transforms_), other.variable_joint_transforms_, bytes);
181 for (
const auto& attached_body : other.attached_body_map_)
182 attachBody(std::make_unique<AttachedBody>(*attached_body.second));
185 bool RobotState::checkJointTransforms(
const JointModel* joint)
const
189 RCLCPP_WARN(LOGGER,
"Returning dirty joint transforms for joint '%s'", joint->getName().c_str());
195 bool RobotState::checkLinkTransforms()
const
199 RCLCPP_WARN(LOGGER,
"Returning dirty link transforms");
205 bool RobotState::checkCollisionTransforms()
const
209 RCLCPP_WARN(LOGGER,
"Returning dirty collision body transforms");
215 void RobotState::markVelocity()
219 has_velocity_ =
true;
220 memset(velocity_, 0,
sizeof(
double) * robot_model_->getVariableCount());
224 void RobotState::markAcceleration()
226 if (!has_acceleration_)
228 has_acceleration_ =
true;
230 memset(acceleration_, 0,
sizeof(
double) * robot_model_->getVariableCount());
234 void RobotState::markEffort()
238 has_acceleration_ =
false;
240 memset(effort_, 0,
sizeof(
double) * robot_model_->getVariableCount());
246 has_velocity_ =
false;
252 has_acceleration_ =
false;
264 has_velocity_ =
false;
269 has_acceleration_ =
false;
287 robot_model_->getVariableRandomPositions(rng, position_);
288 memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() *
sizeof(
unsigned char));
289 dirty_link_transforms_ = robot_model_->getRootJoint();
302 const std::vector<const JointModel*>& joints =
group->getActiveJointModels();
304 joint->getVariableRandomPositions(rng, position_ + joint->getFirstVariableIndex());
305 updateMimicJoints(
group);
309 const std::vector<double>& distances)
318 const std::vector<double>& distances,
319 random_numbers::RandomNumberGenerator& rng)
321 const std::vector<const JointModel*>& joints =
group->getActiveJointModels();
322 assert(distances.size() == joints.size());
323 for (std::size_t i = 0; i < joints.size(); ++i)
325 const int idx = joints[i]->getFirstVariableIndex();
326 joints[i]->getVariableRandomPositionsNearBy(rng, position_ + joints[i]->getFirstVariableIndex(),
327 seed.position_ + idx, distances[i]);
329 updateMimicJoints(
group);
341 random_numbers::RandomNumberGenerator& rng)
343 const std::vector<const JointModel*>& joints =
group->getActiveJointModels();
346 const int idx = joint->getFirstVariableIndex();
347 joint->getVariableRandomPositionsNearBy(rng, position_ + joint->getFirstVariableIndex(), seed.position_ + idx,
350 updateMimicJoints(
group);
355 std::map<std::string, double> m;
356 bool r =
group->getVariableDefaultPositions(
name, m);
363 robot_model_->getVariableDefaultPositions(position_);
365 memset(velocity_, 0,
sizeof(
double) * 2 * robot_model_->getVariableCount());
366 memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() *
sizeof(
unsigned char));
367 dirty_link_transforms_ = robot_model_->getRootJoint();
373 memcpy(position_, position, robot_model_->getVariableCount() *
sizeof(
double));
378 memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() *
sizeof(
unsigned char));
379 dirty_link_transforms_ = robot_model_->getRootJoint();
384 for (
const std::pair<const std::string, double>& it : variable_map)
386 const int index = robot_model_->getVariableIndex(it.first);
387 position_[index] = it.second;
388 const JointModel* jm = robot_model_->getJointOfVariable(index);
389 markDirtyJointTransforms(jm);
390 updateMimicJoint(jm);
394 void RobotState::getMissingKeys(
const std::map<std::string, double>& variable_map,
395 std::vector<std::string>& missing_variables)
const
397 missing_variables.clear();
398 const std::vector<std::string>& nm = robot_model_->getVariableNames();
399 for (
const std::string& variable_name : nm)
401 if (variable_map.find(variable_name) == variable_map.end())
403 if (robot_model_->getJointOfVariable(variable_name)->getMimic() ==
nullptr)
404 missing_variables.push_back(variable_name);
410 std::vector<std::string>& missing_variables)
413 getMissingKeys(variable_map, missing_variables);
417 const std::vector<double>& variable_position)
419 for (std::size_t i = 0; i < variable_names.size(); ++i)
421 const int index = robot_model_->getVariableIndex(variable_names[i]);
422 position_[index] = variable_position[i];
423 const JointModel* jm = robot_model_->getJointOfVariable(index);
424 markDirtyJointTransforms(jm);
425 updateMimicJoint(jm);
432 for (
const std::pair<const std::string, double>& it : variable_map)
433 velocity_[robot_model_->getVariableIndex(it.first)] = it.second;
437 std::vector<std::string>& missing_variables)
440 getMissingKeys(variable_map, missing_variables);
444 const std::vector<double>& variable_velocity)
447 assert(variable_names.size() == variable_velocity.size());
448 for (std::size_t i = 0; i < variable_names.size(); ++i)
449 velocity_[robot_model_->getVariableIndex(variable_names[i])] = variable_velocity[i];
455 for (
const std::pair<const std::string, double>& it : variable_map)
456 acceleration_[robot_model_->getVariableIndex(it.first)] = it.second;
460 std::vector<std::string>& missing_variables)
463 getMissingKeys(variable_map, missing_variables);
467 const std::vector<double>& variable_acceleration)
470 assert(variable_names.size() == variable_acceleration.size());
471 for (std::size_t i = 0; i < variable_names.size(); ++i)
472 acceleration_[robot_model_->getVariableIndex(variable_names[i])] = variable_acceleration[i];
478 for (
const std::pair<const std::string, double>& it : variable_map)
479 effort_[robot_model_->getVariableIndex(it.first)] = it.second;
483 std::vector<std::string>& missing_variables)
486 getMissingKeys(variable_map, missing_variables);
490 const std::vector<double>& variable_effort)
493 assert(variable_names.size() == variable_effort.size());
494 for (std::size_t i = 0; i < variable_names.size(); ++i)
495 effort_[robot_model_->getVariableIndex(variable_names[i])] = variable_effort[i];
502 for (
size_t i = 0; i < robot_model_->getVariableCount(); ++i)
509 if (has_acceleration_)
511 RCLCPP_ERROR(LOGGER,
"Unable to set joint efforts because array is being used for accelerations");
521 const std::vector<int>& il =
group->getVariableIndexList();
522 if (
group->isContiguousWithinState())
524 memcpy(position_ + il[0], gstate,
group->getVariableCount() *
sizeof(
double));
528 for (std::size_t i = 0; i < il.size(); ++i)
529 position_[il[i]] = gstate[i];
531 updateMimicJoints(
group);
536 const std::vector<int>& il =
group->getVariableIndexList();
537 for (std::size_t i = 0; i < il.size(); ++i)
538 position_[il[i]] = values(i);
539 updateMimicJoints(
group);
544 assert(gstate.size() ==
group->getActiveVariableCount());
549 i += jm->getVariableCount();
551 updateMimicJoints(
group);
556 assert(values.size() ==
group->getActiveVariableCount());
561 i += jm->getVariableCount();
563 updateMimicJoints(
group);
568 const std::vector<int>& il =
group->getVariableIndexList();
569 if (
group->isContiguousWithinState())
571 memcpy(gstate, position_ + il[0],
group->getVariableCount() *
sizeof(
double));
575 for (std::size_t i = 0; i < il.size(); ++i)
576 gstate[i] = position_[il[i]];
582 const std::vector<int>& il =
group->getVariableIndexList();
583 values.resize(il.size());
584 for (std::size_t i = 0; i < il.size(); ++i)
585 values(i) = position_[il[i]];
591 const std::vector<int>& il =
group->getVariableIndexList();
592 if (
group->isContiguousWithinState())
594 memcpy(velocity_ + il[0], gstate,
group->getVariableCount() *
sizeof(
double));
598 for (std::size_t i = 0; i < il.size(); ++i)
599 velocity_[il[i]] = gstate[i];
606 const std::vector<int>& il =
group->getVariableIndexList();
607 for (std::size_t i = 0; i < il.size(); ++i)
608 velocity_[il[i]] = values(i);
613 const std::vector<int>& il =
group->getVariableIndexList();
614 if (
group->isContiguousWithinState())
616 memcpy(gstate, velocity_ + il[0],
group->getVariableCount() *
sizeof(
double));
620 for (std::size_t i = 0; i < il.size(); ++i)
621 gstate[i] = velocity_[il[i]];
627 const std::vector<int>& il =
group->getVariableIndexList();
628 values.resize(il.size());
629 for (std::size_t i = 0; i < il.size(); ++i)
630 values(i) = velocity_[il[i]];
636 const std::vector<int>& il =
group->getVariableIndexList();
637 if (
group->isContiguousWithinState())
639 memcpy(acceleration_ + il[0], gstate,
group->getVariableCount() *
sizeof(
double));
643 for (std::size_t i = 0; i < il.size(); ++i)
644 acceleration_[il[i]] = gstate[i];
651 const std::vector<int>& il =
group->getVariableIndexList();
652 for (std::size_t i = 0; i < il.size(); ++i)
653 acceleration_[il[i]] = values(i);
658 const std::vector<int>& il =
group->getVariableIndexList();
659 if (
group->isContiguousWithinState())
661 memcpy(gstate, acceleration_ + il[0],
group->getVariableCount() *
sizeof(
double));
665 for (std::size_t i = 0; i < il.size(); ++i)
666 gstate[i] = acceleration_[il[i]];
672 const std::vector<int>& il =
group->getVariableIndexList();
673 values.resize(il.size());
674 for (std::size_t i = 0; i < il.size(); ++i)
675 values(i) = acceleration_[il[i]];
683 memset(dirty_joint_transforms_, 1, robot_model_->getJointModelCount() *
sizeof(
unsigned char));
684 dirty_link_transforms_ = robot_model_->getRootJoint();
693 if (dirty_link_transforms_ !=
nullptr)
696 if (dirty_collision_body_transforms_ !=
nullptr)
699 dirty_collision_body_transforms_ =
nullptr;
703 const EigenSTL::vector_Isometry3d& ot = link->getCollisionOriginTransforms();
704 const std::vector<int>& ot_id = link->areCollisionOriginTransformsIdentity();
705 const int index_co = link->getFirstCollisionBodyTransformIndex();
706 const int index_l = link->getLinkIndex();
707 for (std::size_t j = 0, end = ot.size(); j != end; ++j)
711 global_collision_body_transforms_[index_co + j] = global_link_transforms_[index_l];
715 global_collision_body_transforms_[index_co + j].affine().noalias() =
716 global_link_transforms_[index_l].affine() * ot[j].matrix();
725 if (dirty_link_transforms_ !=
nullptr)
727 updateLinkTransformsInternal(dirty_link_transforms_);
728 if (dirty_collision_body_transforms_)
730 dirty_collision_body_transforms_ =
731 robot_model_->getCommonRoot(dirty_collision_body_transforms_, dirty_link_transforms_);
735 dirty_collision_body_transforms_ = dirty_link_transforms_;
737 dirty_link_transforms_ =
nullptr;
741 void RobotState::updateLinkTransformsInternal(
const JointModel* start)
745 int idx_link = link->getLinkIndex();
750 if (link->parentJointIsFixed())
752 global_link_transforms_[idx_link].affine().noalias() =
753 global_link_transforms_[idx_parent].affine() * link->getJointOriginTransform().matrix();
757 if (link->jointOriginTransformIsIdentity())
759 global_link_transforms_[idx_link].affine().noalias() =
760 global_link_transforms_[idx_parent].affine() *
getJointTransform(link->getParentJointModel()).matrix();
764 global_link_transforms_[idx_link].affine().noalias() =
765 global_link_transforms_[idx_parent].affine() * link->getJointOriginTransform().matrix() *
772 if (link->jointOriginTransformIsIdentity())
774 global_link_transforms_[idx_link] =
getJointTransform(link->getParentJointModel());
778 global_link_transforms_[idx_link].affine().noalias() =
779 link->getJointOriginTransform().affine() *
getJointTransform(link->getParentJointModel()).matrix();
785 for (
const auto& attached_body : attached_body_map_)
787 attached_body.second->computeTransform(
788 global_link_transforms_[attached_body.second->getAttachedLink()->getLinkIndex()]);
797 if (dirty_collision_body_transforms_)
799 dirty_collision_body_transforms_ =
800 robot_model_->getCommonRoot(dirty_collision_body_transforms_, link->
getParentJointModel());
807 global_link_transforms_[link->
getLinkIndex()] = transform;
812 updateLinkTransformsInternal(joint);
821 child_link = parent_link;
837 updateLinkTransformsInternal(joint);
845 for (
const auto& attached_body : attached_body_map_)
848 global_link_transforms_[attached_body.second->getAttachedLink()->getLinkIndex()]);
857 if ((idx = frame.find(
'/')) != std::string::npos)
859 std::string
object{ frame.substr(0, idx) };
863 if (!body->hasSubframeTransform(frame))
874 return getRobotModel()->getRigidlyConnectedParentLinkModel(link);
879 const std::vector<const JointModel*>& jm = robot_model_->getActiveJointModels();
890 const std::vector<const JointModel*>& jm =
group->getActiveJointModels();
901 const std::vector<const JointModel*>& jm = robot_model_->getActiveJointModels();
915 for (
const JointModel* jm : robot_model_->getActiveJointModels())
935 std::pair<double, const JointModel*>
938 double distance = std::numeric_limits<double>::max();
952 std::vector<double> lower_bounds(bounds.size()), upper_bounds(bounds.size());
953 for (std::size_t j = 0; j < bounds.size(); ++j)
955 lower_bounds[j] = bounds[j].min_position_;
956 upper_bounds[j] = bounds[j].max_position_;
958 double new_distance = joint->distance(joint_values, &lower_bounds[0]);
964 new_distance = joint->distance(joint_values, &upper_bounds[0]);
971 return std::make_pair(
distance, index);
976 const std::vector<const JointModel*>& jm =
group->getActiveJointModels();
979 const int idx = joint_id->getFirstVariableIndex();
980 const std::vector<VariableBounds>& bounds = joint_id->getVariableBounds();
983 for (std::size_t var_id = 0; var_id < joint_id->getVariableCount(); ++var_id)
985 const double dtheta = std::abs(*(position_ + idx + var_id) - *(other.
getVariablePositions() + idx + var_id));
987 if (dtheta > dt * bounds[var_id].max_velocity_)
1000 const int idx = joint->getFirstVariableIndex();
1001 d += joint->getDistanceFactor() * joint->distance(position_ + idx, other.position_ + idx);
1008 moveit::core::checkInterpolationParamBounds(LOGGER, t);
1011 memset(state.dirty_joint_transforms_, 1, state.robot_model_->getJointModelCount() *
sizeof(
unsigned char));
1012 state.dirty_link_transforms_ = state.robot_model_->getRootJoint();
1017 moveit::core::checkInterpolationParamBounds(LOGGER, t);
1021 const int idx = joint->getFirstVariableIndex();
1022 joint->interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
1024 state.updateMimicJoints(joint_group);
1029 attached_body_update_callback_ = callback;
1034 return attached_body_map_.find(
id) != attached_body_map_.end();
1039 const auto it = attached_body_map_.find(
id);
1040 if (it == attached_body_map_.end())
1042 RCLCPP_ERROR(LOGGER,
"Attached body '%s' not found",
id.c_str());
1046 return it->second.get();
1055 if (attached_body_update_callback_)
1056 attached_body_update_callback_(attached_body.get(),
true);
1057 attached_body_map_[attached_body->getName()] = std::move(attached_body);
1062 attachBody(std::unique_ptr<AttachedBody>(attached_body));
1066 const std::vector<shapes::ShapeConstPtr>&
shapes,
1067 const EigenSTL::vector_Isometry3d& shape_poses,
const std::set<std::string>& touch_links,
1068 const std::string& link,
const trajectory_msgs::msg::JointTrajectory& detach_posture,
1071 attachBody(std::make_unique<AttachedBody>(robot_model_->getLinkModel(link),
id, pose,
shapes, shape_poses,
1072 touch_links, detach_posture, subframe_poses));
1077 attached_bodies.clear();
1078 attached_bodies.reserve(attached_body_map_.size());
1079 for (
const auto& it : attached_body_map_)
1080 attached_bodies.push_back(it.second.get());
1085 attached_bodies.clear();
1086 for (
const auto& it : attached_body_map_)
1088 if (
group->hasLinkModel(it.second->getAttachedLinkName()))
1089 attached_bodies.push_back(it.second.get());
1095 attached_bodies.clear();
1096 for (
const auto& it : attached_body_map_)
1098 if (it.second->getAttachedLink() == link_model)
1099 attached_bodies.push_back(it.second.get());
1105 for (
const auto& it : attached_body_map_)
1107 if (attached_body_update_callback_)
1108 attached_body_update_callback_(it.second.get(),
false);
1110 attached_body_map_.clear();
1115 for (
auto it = attached_body_map_.cbegin(); it != attached_body_map_.cend(); ++it)
1117 if (it->second->getAttachedLink() != link)
1121 if (attached_body_update_callback_)
1122 attached_body_update_callback_(it->second.get(),
false);
1123 const auto del = it++;
1124 attached_body_map_.erase(del);
1130 for (
auto it = attached_body_map_.cbegin(); it != attached_body_map_.cend(); ++it)
1132 if (!
group->hasLinkModel(it->second->getAttachedLinkName()))
1136 if (attached_body_update_callback_)
1137 attached_body_update_callback_(it->second.get(),
false);
1138 const auto del = it++;
1139 attached_body_map_.erase(del);
1145 const auto it = attached_body_map_.find(
id);
1146 if (it != attached_body_map_.end())
1148 if (attached_body_update_callback_)
1149 attached_body_update_callback_(it->second.get(),
false);
1150 attached_body_map_.erase(it);
1167 const auto& result =
getFrameInfo(frame_id, ignored_link, found);
1171 *frame_found = found;
1175 RCLCPP_WARN(LOGGER,
"getFrameTransform() did not find a frame with name %s.", frame_id.c_str());
1182 bool& frame_found)
const
1184 if (!frame_id.empty() && frame_id[0] ==
'/')
1185 return getFrameInfo(frame_id.substr(1), robot_link, frame_found);
1187 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
1188 if (frame_id == robot_model_->getModelFrame())
1190 robot_link = robot_model_->getRootLink();
1192 return IDENTITY_TRANSFORM;
1194 if ((robot_link = robot_model_->getLinkModel(frame_id, &frame_found)))
1196 assert(checkLinkTransforms());
1197 return global_link_transforms_[robot_link->
getLinkIndex()];
1199 robot_link =
nullptr;
1202 const auto jt = attached_body_map_.find(frame_id);
1203 if (jt != attached_body_map_.end())
1205 const Eigen::Isometry3d& transform = jt->second->getGlobalPose();
1206 robot_link = jt->second->getAttachedLink();
1208 assert(checkLinkTransforms());
1213 for (
const auto& body : attached_body_map_)
1215 const Eigen::Isometry3d& transform = body.second->getGlobalSubframeTransform(frame_id, &frame_found);
1218 robot_link = body.second->getAttachedLink();
1219 assert(checkLinkTransforms());
1224 robot_link =
nullptr;
1225 frame_found =
false;
1226 return IDENTITY_TRANSFORM;
1231 if (!frame_id.empty() && frame_id[0] ==
'/')
1233 if (robot_model_->hasLinkModel(frame_id))
1237 const auto it = attached_body_map_.find(frame_id);
1238 if (it != attached_body_map_.end())
1239 return !it->second->getGlobalCollisionBodyTransforms().empty();
1242 for (
const auto& body : attached_body_map_)
1244 if (body.second->hasSubframeTransform(frame_id))
1251 const std_msgs::msg::ColorRGBA& color,
const std::string& ns,
1252 const rclcpp::Duration& dur,
bool include_attached)
const
1254 std::size_t cur_num = arr.markers.size();
1256 unsigned int id = cur_num;
1257 for (std::size_t i = cur_num; i < arr.markers.size(); ++i, ++id)
1259 arr.markers[i].ns = ns;
1260 arr.markers[i].id = id;
1261 arr.markers[i].lifetime = dur;
1262 arr.markers[i].color = color;
1267 bool include_attached)
const
1269 rclcpp::Clock clock;
1270 for (
const std::string& link_name : link_names)
1272 RCLCPP_DEBUG(LOGGER,
"Trying to get marker for link '%s'", link_name.c_str());
1273 const LinkModel* link_model = robot_model_->getLinkModel(link_name);
1276 if (include_attached)
1278 for (
const auto& it : attached_body_map_)
1280 if (it.second->getAttachedLink() == link_model)
1282 for (std::size_t j = 0; j < it.second->getShapes().size(); ++j)
1284 visualization_msgs::msg::Marker att_mark;
1285 att_mark.header.frame_id = robot_model_->getModelFrame();
1286 att_mark.header.stamp = clock.now();
1287 if (shapes::constructMarkerFromShape(it.second->getShapes()[j].get(), att_mark))
1290 if (fabs(att_mark.scale.x * att_mark.scale.y * att_mark.scale.z) < std::numeric_limits<double>::epsilon())
1292 att_mark.pose = tf2::toMsg(it.second->getGlobalCollisionBodyTransforms()[j]);
1293 arr.markers.push_back(att_mark);
1303 for (std::size_t j = 0; j < link_model->
getShapes().size(); ++j)
1305 visualization_msgs::msg::Marker mark;
1306 mark.header.frame_id = robot_model_->getModelFrame();
1307 mark.header.stamp = clock.now();
1311 if (mesh_resource.empty() || link_model->
getShapes().size() > 1)
1313 if (!shapes::constructMarkerFromShape(link_model->
getShapes()[j].get(), mark))
1316 if (fabs(mark.scale.x * mark.scale.y * mark.scale.z) < std::numeric_limits<double>::epsilon())
1323 mark.type = mark.MESH_RESOURCE;
1324 mark.mesh_use_embedded_materials =
false;
1325 mark.mesh_resource = mesh_resource;
1328 mark.scale.x = mesh_scale[0];
1329 mark.scale.y = mesh_scale[1];
1330 mark.scale.z = mesh_scale[2];
1334 arr.markers.push_back(mark);
1342 Eigen::MatrixXd result;
1344 throw Exception(
"Unable to compute Jacobian");
1349 const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian,
1350 bool use_quaternion_representation)
const
1352 assert(checkLinkTransforms());
1354 if (!
group->isChain())
1356 RCLCPP_ERROR(LOGGER,
"The group '%s' is not a chain. Cannot compute Jacobian.",
group->getName().c_str());
1362 RCLCPP_ERROR(LOGGER,
"Link name '%s' does not exist in the chain '%s' or is not a child for this chain",
1370 Eigen::Isometry3d reference_transform =
1372 int rows = use_quaternion_representation ? 7 : 6;
1373 int columns =
group->getVariableCount();
1374 jacobian = Eigen::MatrixXd::Zero(rows, columns);
1378 Eigen::Vector3d point_transform = link_transform * reference_point_position;
1386 Eigen::Isometry3d joint_transform;
1404 unsigned int joint_index =
group->getVariableGroupIndex(pjm->
getName());
1410 jacobian.block<3, 1>(0, joint_index) =
1411 jacobian.block<3, 1>(0, joint_index) + joint_axis.cross(point_transform - joint_transform.translation());
1412 jacobian.block<3, 1>(3, joint_index) = jacobian.block<3, 1>(3, joint_index) + joint_axis;
1417 jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1422 jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1424 jacobian.block<3, 1>(0, joint_index + 1) = jacobian.block<3, 1>(0, joint_index + 1) + joint_axis;
1426 jacobian.block<3, 1>(0, joint_index + 2) = jacobian.block<3, 1>(0, joint_index + 2) +
1427 joint_axis.cross(point_transform - joint_transform.translation());
1428 jacobian.block<3, 1>(3, joint_index + 2) = jacobian.block<3, 1>(3, joint_index + 2) + joint_axis;
1431 RCLCPP_ERROR(LOGGER,
"Unknown type of joint in Jacobian computation");
1433 if (pjm == root_joint_model)
1437 if (use_quaternion_representation)
1444 Eigen::Quaterniond q(link_transform.linear());
1445 double w = q.w(), x = q.x(), y = q.y(), z = q.z();
1446 Eigen::MatrixXd quaternion_update_matrix(4, 3);
1447 quaternion_update_matrix << -x, -y, -z, w, -z, y, z, w, -x, -y, x, w;
1448 jacobian.block(3, 0, 4, columns) = 0.5 * quaternion_update_matrix * jacobian.block(3, 0, 3, columns);
1456 Eigen::VectorXd qdot;
1464 Eigen::Matrix<double, 6, 1> t;
1465 tf2::fromMsg(twist, t);
1470 const Eigen::VectorXd& twist,
const LinkModel* tip)
const
1479 Eigen::MatrixXd e_wb = Eigen::ArrayXXd::Zero(6, 6);
1480 e_wb.block(0, 0, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
1481 e_wb.block(3, 3, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
1485 Eigen::JacobiSVD<Eigen::MatrixXd> svd_of_j(j, Eigen::ComputeThinU | Eigen::ComputeThinV);
1486 const Eigen::MatrixXd& u = svd_of_j.matrixU();
1487 const Eigen::MatrixXd& v = svd_of_j.matrixV();
1488 const Eigen::VectorXd& s = svd_of_j.singularValues();
1490 Eigen::VectorXd sinv = s;
1491 static const double PINVTOLER = std::numeric_limits<double>::epsilon();
1493 for (std::size_t i = 0; i < static_cast<std::size_t>(s.rows()); ++i)
1495 if (fabs(s(i)) > maxsv)
1498 for (std::size_t i = 0; i < static_cast<std::size_t>(s.rows()); ++i)
1501 if (fabs(s(i)) > maxsv * PINVTOLER)
1503 sinv(i) = 1.0 / s(i);
1510 Eigen::MatrixXd jinv = (v * sinv.asDiagonal() * u.transpose());
1513 qdot = jinv * twist;
1527 std::vector<double> values;
1529 return constraint(
this, jmg, &values[0]);
1543 RCLCPP_ERROR(LOGGER,
"No kinematics solver instantiated for group '%s'", jmg->
getName().c_str());
1546 return setFromIK(jmg, pose, solver->getTipFrame(), timeout, constraint,
options, cost_function);
1554 Eigen::Isometry3d mat;
1555 tf2::fromMsg(pose, mat);
1556 static std::vector<double> consistency_limits;
1557 return setFromIK(jmg, mat, tip, consistency_limits, timeout, constraint,
options, cost_function);
1568 RCLCPP_ERROR(LOGGER,
"No kinematics solver instantiated for group '%s'", jmg->
getName().c_str());
1571 static std::vector<double> consistency_limits;
1572 return setFromIK(jmg, pose, solver->getTipFrame(), consistency_limits, timeout, constraint,
options, cost_function);
1580 static std::vector<double> consistency_limits;
1581 return setFromIK(jmg, pose_in, tip_in, consistency_limits, timeout, constraint,
options, cost_function);
1588 const std::vector<double>& ik_sol, moveit_msgs::msg::MoveItErrorCodes& error_code)
1590 const std::vector<size_t>& bij =
group->getKinematicsSolverJointBijection();
1591 std::vector<double> solution(bij.size());
1592 for (std::size_t i = 0; i < bij.size(); ++i)
1593 solution[bij[i]] = ik_sol[i];
1594 if (constraint(state,
group, &solution[0]))
1596 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1600 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
1617 getLinkModel((!ik_frame.empty() && ik_frame[0] ==
'/') ? ik_frame.substr(1) : ik_frame);
1620 RCLCPP_ERROR(LOGGER,
"The following IK frame does not exist: %s", ik_frame.c_str());
1629 const std::vector<double>& consistency_limits_in,
double timeout,
1635 EigenSTL::vector_Isometry3d poses;
1636 poses.push_back(pose_in);
1638 std::vector<std::string> tips;
1639 tips.push_back(tip_in);
1641 std::vector<std::vector<double> > consistency_limits;
1642 consistency_limits.push_back(consistency_limits_in);
1644 return setFromIK(jmg, poses, tips, consistency_limits, timeout, constraint,
options, cost_function);
1648 const std::vector<std::string>& tips_in,
double timeout,
1653 const std::vector<std::vector<double> > consistency_limits;
1654 return setFromIK(jmg, poses_in, tips_in, consistency_limits, timeout, constraint,
options, cost_function);
1658 const std::vector<std::string>& tips_in,
1659 const std::vector<std::vector<double> >& consistency_limit_sets,
double timeout,
1665 if (poses_in.size() != tips_in.size())
1667 RCLCPP_ERROR(LOGGER,
"Number of poses must be the same as number of tips");
1675 bool valid_solver =
true;
1678 valid_solver =
false;
1681 else if (poses_in.size() > 1)
1683 std::string error_msg;
1684 if (!solver->supportsGroup(jmg, &error_msg))
1687 RCLCPP_ERROR(LOGGER,
"Kinematics solver %s does not support joint group %s. Error: %s",
1688 typeid(solver_ref).
name(), jmg->
getName().c_str(), error_msg.c_str());
1689 valid_solver =
false;
1696 if (poses_in.size() > 1)
1703 RCLCPP_ERROR(LOGGER,
"No kinematics solver instantiated for group '%s'", jmg->
getName().c_str());
1709 std::vector<double> consistency_limits;
1710 if (consistency_limit_sets.size() > 1)
1712 RCLCPP_ERROR(LOGGER,
1713 "Invalid number (%zu) of sets of consistency limits for a setFromIK request "
1714 "that is being solved by a single IK solver",
1715 consistency_limit_sets.size());
1718 else if (consistency_limit_sets.size() == 1)
1719 consistency_limits = consistency_limit_sets[0];
1721 const std::vector<std::string>& solver_tip_frames = solver->getTipFrames();
1724 std::vector<bool> tip_frames_used(solver_tip_frames.size(),
false);
1727 std::vector<geometry_msgs::msg::Pose> ik_queries(solver_tip_frames.size());
1730 for (std::size_t i = 0; i < poses_in.size(); ++i)
1733 Eigen::Isometry3d pose = poses_in[i];
1734 std::string pose_frame = tips_in[i];
1737 if (!pose_frame.empty() && pose_frame[0] ==
'/')
1738 pose_frame = pose_frame.substr(1);
1746 bool found_valid_frame =
false;
1747 std::size_t solver_tip_id;
1748 for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1751 if (tip_frames_used[solver_tip_id])
1755 std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1759 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1760 solver_tip_frame = solver_tip_frame.substr(1);
1762 if (pose_frame != solver_tip_frame)
1767 pose_frame = body->getAttachedLinkName();
1768 pose = pose * body->getPose().inverse();
1770 if (pose_frame != solver_tip_frame)
1775 RCLCPP_ERROR(LOGGER,
"The following Pose Frame does not exist: %s", pose_frame.c_str());
1779 for (
const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
1783 pose_frame = solver_tip_frame;
1784 pose = pose * fixed_link.second;
1793 if (pose_frame == solver_tip_frame)
1795 found_valid_frame =
true;
1802 if (!found_valid_frame)
1804 RCLCPP_ERROR(LOGGER,
"Cannot compute IK for query %zu pose reference frame '%s'", i, pose_frame.c_str());
1806 std::stringstream ss;
1807 for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1808 ss << solver_tip_frames[solver_tip_id] <<
", ";
1809 RCLCPP_ERROR(LOGGER,
"Available tip frames: [%s]", ss.str().c_str());
1814 tip_frames_used[solver_tip_id] =
true;
1817 geometry_msgs::msg::Pose ik_query;
1818 ik_query = tf2::toMsg(pose);
1821 ik_queries[solver_tip_id] = ik_query;
1825 for (std::size_t solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1828 if (tip_frames_used[solver_tip_id])
1832 std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1836 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1837 solver_tip_frame = solver_tip_frame.substr(1);
1847 geometry_msgs::msg::Pose ik_query;
1848 ik_query = tf2::toMsg(current_pose);
1851 ik_queries[solver_tip_id] = ik_query;
1854 tip_frames_used[solver_tip_id] =
true;
1858 if (timeout < std::numeric_limits<double>::epsilon())
1865 ik_callback_fn = ik_callback_fn = [
this, jmg, constraint](
const geometry_msgs::msg::Pose& pose,
1866 const std::vector<double>& joints,
1867 moveit_msgs::msg::MoveItErrorCodes& error_code) {
1868 ikCallbackFnAdapter(
this, jmg, constraint, pose, joints, error_code);
1875 std::vector<double> initial_values;
1877 std::vector<double> seed(bij.size());
1878 for (std::size_t i = 0; i < bij.size(); ++i)
1879 seed[i] = initial_values[bij[i]];
1882 std::vector<double> ik_sol;
1883 moveit_msgs::msg::MoveItErrorCodes error;
1885 if (solver->searchPositionIK(ik_queries, seed, timeout, consistency_limits, ik_sol, ik_callback_fn, cost_function,
1888 std::vector<double> solution(bij.size());
1889 for (std::size_t i = 0; i < bij.size(); ++i)
1890 solution[bij[i]] = ik_sol[i];
1898 const std::vector<std::string>& tips_in,
1899 const std::vector<std::vector<double> >& consistency_limits,
double timeout,
1906 std::vector<const JointModelGroup*> sub_groups;
1910 if (poses_in.size() != sub_groups.size())
1912 RCLCPP_ERROR(LOGGER,
"Number of poses (%zu) must be the same as number of sub-groups (%zu)", poses_in.size(),
1917 if (tips_in.size() != sub_groups.size())
1919 RCLCPP_ERROR(LOGGER,
"Number of tip names (%zu) must be same as number of sub-groups (%zu)", tips_in.size(),
1924 if (!consistency_limits.empty() && consistency_limits.size() != sub_groups.size())
1926 RCLCPP_ERROR(LOGGER,
"Number of consistency limit vectors must be the same as number of sub-groups");
1930 for (std::size_t i = 0; i < consistency_limits.size(); ++i)
1934 RCLCPP_ERROR(LOGGER,
"Number of joints in consistency_limits is %zu but it should be should be %u", i,
1941 std::vector<kinematics::KinematicsBaseConstPtr> solvers;
1942 for (std::size_t i = 0; i < poses_in.size(); ++i)
1944 kinematics::KinematicsBaseConstPtr solver = sub_groups[i]->getSolverInstance();
1947 RCLCPP_ERROR(LOGGER,
"Could not find solver for group '%s'", sub_groups[i]->getName().c_str());
1950 solvers.push_back(solver);
1954 EigenSTL::vector_Isometry3d transformed_poses = poses_in;
1955 std::vector<std::string> pose_frames = tips_in;
1958 for (std::size_t i = 0; i < poses_in.size(); ++i)
1960 ASSERT_ISOMETRY(transformed_poses[i])
1961 Eigen::Isometry3d& pose = transformed_poses[i];
1962 std::string& pose_frame = pose_frames[i];
1969 std::string solver_tip_frame = solvers[i]->getTipFrame();
1973 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1974 solver_tip_frame = solver_tip_frame.substr(1);
1976 if (pose_frame != solver_tip_frame)
1982 pose = pose * body->
getPose().inverse();
1984 if (pose_frame != solver_tip_frame)
1991 for (
const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
1993 if (fixed_link.first->getName() == solver_tip_frame)
1995 pose_frame = solver_tip_frame;
1996 pose = pose * fixed_link.second;
2003 if (pose_frame != solver_tip_frame)
2005 RCLCPP_ERROR(LOGGER,
"Cannot compute IK for query pose reference frame '%s', desired: '%s'", pose_frame.c_str(),
2006 solver_tip_frame.c_str());
2012 std::vector<geometry_msgs::msg::Pose> ik_queries(poses_in.size());
2016 ik_callback_fn = [
this, jmg, constraint](
const geometry_msgs::msg::Pose pose,
const std::vector<double>& joints,
2017 moveit_msgs::msg::MoveItErrorCodes& error_code) {
2018 ikCallbackFnAdapter(
this, jmg, constraint, pose, joints, error_code);
2022 for (std::size_t i = 0; i < transformed_poses.size(); ++i)
2024 Eigen::Quaterniond quat(transformed_poses[i].linear());
2026 ik_queries[i].position.x = point.x();
2027 ik_queries[i].position.y = point.y();
2028 ik_queries[i].position.z = point.z();
2029 ik_queries[i].orientation.x = quat.x();
2030 ik_queries[i].orientation.y = quat.y();
2031 ik_queries[i].orientation.z = quat.z();
2032 ik_queries[i].orientation.w = quat.w();
2036 if (timeout < std::numeric_limits<double>::epsilon())
2039 auto start = std::chrono::system_clock::now();
2042 bool first_seed =
true;
2043 unsigned int attempts = 0;
2047 RCLCPP_DEBUG(LOGGER,
"IK attempt: %d", attempts);
2048 bool found_solution =
true;
2049 for (std::size_t sg = 0; sg < sub_groups.size(); ++sg)
2051 const std::vector<size_t>& bij = sub_groups[sg]->getKinematicsSolverJointBijection();
2052 std::vector<double> seed(bij.size());
2056 std::vector<double> initial_values;
2058 for (std::size_t i = 0; i < bij.size(); ++i)
2059 seed[i] = initial_values[bij[i]];
2065 std::vector<double> random_values;
2066 sub_groups[sg]->getVariableRandomPositions(rng, random_values);
2067 for (std::size_t i = 0; i < bij.size(); ++i)
2068 seed[i] = random_values[bij[i]];
2072 std::vector<double> ik_sol;
2073 moveit_msgs::msg::MoveItErrorCodes error;
2074 const std::vector<double>& climits = consistency_limits.empty() ? std::vector<double>() : consistency_limits[sg];
2075 if (solvers[sg]->searchPositionIK(ik_queries[sg], seed, (timeout - elapsed) / sub_groups.size(), climits, ik_sol,
2078 std::vector<double> solution(bij.size());
2079 for (std::size_t i = 0; i < bij.size(); ++i)
2080 solution[bij[i]] = ik_sol[i];
2085 found_solution =
false;
2091 std::vector<double> full_solution;
2093 if (constraint ? constraint(
this, jmg, &full_solution[0]) :
true)
2095 RCLCPP_DEBUG(LOGGER,
"Found IK solution");
2099 elapsed = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - start).count();
2101 }
while (elapsed < timeout);
2107 bool global_reference_frame,
double distance,
double max_step,
2117 const LinkModel* link,
const Eigen::Isometry3d& target,
2118 bool global_reference_frame,
double max_step,
double jump_threshold_factor,
2128 const LinkModel* link,
const EigenSTL::vector_Isometry3d& waypoints,
2129 bool global_reference_frame,
double max_step,
double jump_threshold_factor,
2140 assert(checkLinkTransforms());
2143 std::vector<const LinkModel*> links = robot_model_->getLinkModelsWithCollisionGeometry();
2148 transform.translate(link->getCenteredBoundingBoxOffset());
2151 for (
const auto& it : attached_body_map_)
2153 const EigenSTL::vector_Isometry3d& transforms = it.second->getGlobalCollisionBodyTransforms();
2154 const std::vector<shapes::ShapeConstPtr>&
shapes = it.second->getShapes();
2155 for (std::size_t i = 0; i < transforms.size(); ++i)
2163 aabb.resize(6, 0.0);
2164 if (!bounding_box.isEmpty())
2168 Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(aabb.data(), 3) = bounding_box.min();
2169 Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(aabb.data() + 1, 3) = bounding_box.max();
2175 const std::vector<std::string>& nm = robot_model_->getVariableNames();
2176 for (std::size_t i = 0; i < nm.size(); ++i)
2177 out << nm[i] <<
'=' << position_[i] <<
'\n';
2191 if (joint->getVariableCount() > 1)
2204 out <<
" " << std::fixed << std::setprecision(5) << bound.
min_position_ <<
'\t';
2206 double step = delta / 20.0;
2208 bool marker_shown =
false;
2212 if (!marker_shown && current_value < value)
2215 marker_shown =
true;
2224 out <<
" \t" << std::fixed << std::setprecision(5) << bound.
max_position_ <<
" \t" << joint->getName()
2225 <<
" current: " << std::fixed << std::setprecision(5) << current_value <<
'\n';
2234 out <<
" * Dirty Joint Transforms: \n";
2235 const std::vector<const JointModel*>& jm = robot_model_->getJointModels();
2239 out <<
" " << joint->getName() <<
'\n';
2241 out <<
" * Dirty Link Transforms: " << (dirty_link_transforms_ ? dirty_link_transforms_->
getName() :
"NULL") <<
'\n';
2242 out <<
" * Dirty Collision Body Transforms: "
2243 << (dirty_collision_body_transforms_ ? dirty_collision_body_transforms_->
getName() :
"NULL\n");
2248 out <<
"Robot State @" <<
this <<
'\n';
2250 std::size_t n = robot_model_->getVariableCount();
2253 out <<
" * Position: ";
2254 for (std::size_t i = 0; i < n; ++i)
2255 out << position_[i] <<
' ';
2259 out <<
" * Position: NULL\n";
2263 out <<
" * Velocity: ";
2264 for (std::size_t i = 0; i < n; ++i)
2265 out << velocity_[i] <<
' ';
2269 out <<
" * Velocity: NULL\n";
2273 out <<
" * Acceleration: ";
2274 for (std::size_t i = 0; i < n; ++i)
2275 out << acceleration_[i] <<
' ';
2279 out <<
" * Acceleration: NULL\n";
2281 out <<
" * Dirty Link Transforms: " << (dirty_link_transforms_ ? dirty_link_transforms_->
getName() :
"NULL\n");
2282 out <<
" * Dirty Collision Body Transforms: "
2283 << (dirty_collision_body_transforms_ ? dirty_collision_body_transforms_->
getName() :
"NULL\n");
2290 if (checkIsometry(transform, CHECK_ISOMETRY_PRECISION,
false))
2292 Eigen::Quaterniond q(transform.linear());
2293 out <<
"T.xyz = [" << transform.translation().x() <<
", " << transform.translation().y() <<
", "
2294 << transform.translation().z() <<
"], Q.xyzw = [" << q.x() <<
", " << q.y() <<
", " << q.z() <<
", " << q.w()
2299 out <<
"[NON-ISOMETRY] "
2300 << transform.matrix().format(
2301 Eigen::IOFormat(Eigen::StreamPrecision, Eigen::DontAlignCols,
", ",
"; ",
"",
"",
"[",
"]"));
2308 if (!variable_joint_transforms_)
2310 out <<
"No transforms computed\n";
2314 out <<
"Joint transforms:\n";
2315 const std::vector<const JointModel*>& jm = robot_model_->getJointModels();
2318 out <<
" " << joint->getName();
2319 const int idx = joint->getJointIndex();
2320 if (dirty_joint_transforms_[idx])
2326 out <<
"Link poses:\n";
2327 const std::vector<const LinkModel*>& link_model = robot_model_->getLinkModels();
2328 for (
const LinkModel* link : link_model)
2330 out <<
" " << link->getName() <<
": ";
2331 printTransform(global_link_transforms_[link->getLinkIndex()], out);
2337 std::stringstream ss;
2338 ss <<
"ROBOT: " << robot_model_->getName() <<
'\n';
2339 getStateTreeJointString(ss, robot_model_->getRootJoint(),
" ",
true);
2345 void getPoseString(std::ostream& ss,
const Eigen::Isometry3d& pose,
const std::string& pfx)
2348 for (
int y = 0; y < 4; ++y)
2351 for (
int x = 0; x < 4; ++x)
2353 ss << std::setw(8) << pose(y, x) <<
' ';
2360 void RobotState::getStateTreeJointString(std::ostream& ss,
const JointModel* jm,
const std::string& pfx0,
2363 std::string pfx = pfx0 +
"+--";
2365 ss << pfx <<
"Joint: " << jm->getName() <<
'\n';
2367 pfx = pfx0 + (last ?
" " :
"| ");
2369 for (std::size_t i = 0; i < jm->getVariableCount(); ++i)
2372 ss << pfx << jm->getVariableNames()[i] << std::setw(12) << position_[jm->getFirstVariableIndex() + i] <<
'\n';
2375 const LinkModel* link_model = jm->getChildLinkModel();
2377 ss << pfx <<
"Link: " << link_model->
getName() <<
'\n';
2378 getPoseString(ss, link_model->getJointOriginTransform(), pfx +
"joint_origin:");
2379 if (variable_joint_transforms_)
2381 getPoseString(ss, variable_joint_transforms_[jm->getJointIndex()], pfx +
"joint_variable:");
2382 getPoseString(ss, global_link_transforms_[link_model->getLinkIndex()], pfx +
"link_global:");
2385 for (std::vector<const JointModel*>::const_iterator it = link_model->getChildJointModels().begin();
2386 it != link_model->getChildJointModels().end(); ++it)
2387 getStateTreeJointString(ss, *it, pfx, it + 1 == link_model->getChildJointModels().end());
Provides an interface for kinematics solvers.
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, const moveit::core::JointModelGroup *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
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.
This may be thrown if unrecoverable errors occur.
Represents an axis-aligned bounding box.
void extendWithTransformedBox(const Eigen::Isometry3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
Object defining bodies that can be attached to robot links.
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
const Eigen::Isometry3d & getPose() const
Get the pose of the attached body relative to the parent link.
static Distance computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
double getDefaultIKTimeout() const
Get the default IK timeout.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::string & getName() const
Get the name of the joint group.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
void getSubgroups(std::vector< const JointModelGroup * > &sub_groups) const
Get the groups that are subsets of this one (in terms of joints set)
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...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
size_t getJointIndex() const
Get the index of this joint within the robot model.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
const std::string & getName() const
Get the name of the joint.
const std::vector< const LinkModel * > & getDescendantLinkModels() const
Get all the link models that descend from this joint, in the kinematic tree.
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
JointType getType() const
Get the type of joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
int getFirstCollisionBodyTransformIndex() const
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
const Eigen::Isometry3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
const std::string & getName() const
The name of this link.
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
const std::vector< const JointModel * > & getChildJointModels() const
A link may have 0 or more child joints. From those joints there will certainly be other descendant li...
size_t getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this link.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void zeroVelocities()
Set all velocities to 0.0.
RobotState & operator=(const RobotState &other)
Copy operator.
void setJointEfforts(const JointModel *joint, const double *effort)
void setAttachedBodyUpdateCallback(const AttachedBodyCallback &callback)
void printTransforms(std::ostream &out=std::cout) const
void printTransform(const Eigen::Isometry3d &transform, std::ostream &out=std::cout) const
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
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...
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Isometry3d &transform, bool backward=false)
Update the state after setting a particular link to the input global transform pose.
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
const double * getJointPositions(const std::string &joint_name) const
std::pair< double, const JointModel * > getMinDistanceToPositionBounds() const
Get the minimm distance from this state to the bounds. The minimum distance and the joint for which t...
void copyJointGroupVelocities(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
void setJointGroupAccelerations(const std::string &joint_group_name, const double *gstate)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
void setJointGroupVelocities(const std::string &joint_group_name, const double *gstate)
Given velocities for the variables that make up a group, in the order found in the group (including v...
void computeVariableVelocity(const JointModelGroup *jmg, Eigen::VectorXd &qdot, const Eigen::VectorXd &twist, const LinkModel *tip) const
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and ...
void computeAABB(std::vector< double > &aabb) const
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
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...
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
void harmonizePositions()
Call harmonizePosition() for all joints / all joints in group / given joint.
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
bool dirtyCollisionBodyTransforms() const
void zeroAccelerations()
Set all accelerations to 0.0.
bool isValidVelocityMove(const RobotState &other, const JointModelGroup *group, double dt) const
Check that the time to move between two waypoints is sufficient given velocity limits and time step.
bool setFromDiffIK(const JointModelGroup *group, const Eigen::VectorXd &twist, const std::string &tip, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Set the joint values from a Cartesian velocity applied during a time dt.
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
void printStatePositionsWithJointLimits(const moveit::core::JointModelGroup *jmg, std::ostream &out=std::cout) const
Output to console the current state of the robot's joint limits.
void dropDynamics()
Reduce RobotState to kinematic information (remove velocity, acceleration and effort,...
bool dirtyJointTransform(const JointModel *joint) const
void setToRandomPositionsNearBy(const JointModelGroup *group, const RobotState &seed, double distance)
Set all joints in group to random values near the value in seed. distance is the maximum amount each ...
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
void interpolate(const RobotState &to, double t, RobotState &state) const
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
std::string getStateTreeString() const
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 satisfiesBounds(double margin=0.0) const
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state.
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
bool dirtyLinkTransforms() const
void printStateInfo(std::ostream &out=std::cout) const
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
void update(bool force=false)
Update all transforms.
void dropAccelerations()
Remove accelerations from this state (this differs from setting them to zero)
void getRobotMarkers(visualization_msgs::msg::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::msg::ColorRGBA &color, const std::string &ns, const rclcpp::Duration &dur, bool include_attached=false) const
Get a MarkerArray that fully describes the robot markers for a given robot.
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
bool setFromIKSubgroups(const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
setFromIK for multiple poses and tips (end effectors) when no solver exists for the jmg that can solv...
bool setToIKSolverFrame(Eigen::Isometry3d &pose, const kinematics::KinematicsBaseConstPtr &solver)
Transform pose from the robot model's base frame to the reference frame of the IK solver.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void printStatePositions(std::ostream &out=std::cout) const
std::size_t getVariableCount() const
Get the number of variables that make up this state.
void printDirtyInfo(std::ostream &out=std::cout) const
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
void copyJointGroupAccelerations(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
RobotState(const RobotModelConstPtr &robot_model)
A state can be constructed from a specified robot model. No values are initialized....
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, double max_step, double jump_threshold_factor, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular gr...
void dropEffort()
Remove effort values from this state (this differs from setting them to zero)
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
bool integrateVariableVelocity(const JointModelGroup *jmg, const Eigen::VectorXd &qdot, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Given the velocities for the variables in this group (qdot) and an amount of time (dt),...
bool hasAttachedBody(const std::string &id) const
Check if an attached body named id exists in this state.
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
void invertVelocity()
Invert velocity if present.
const Eigen::Isometry3d & getFrameInfo(const std::string &frame_id, const LinkModel *&robot_link, bool &frame_found) const
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void harmonizePosition(const JointModel *joint)
void clearAttachedBodies()
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed.
void dropVelocities()
Remove velocities from this state (this differs from setting them to zero)
void zeroEffort()
Set all effort values to 0.0.
const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const std::string &frame) const
Get the latest link upwards the kinematic tree which is only connected via fixed joints.
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
void setJointPositions(const std::string &joint_name, const double *position)
#define MOVEIT_CONSOLE_COLOR_RESET
#define MOVEIT_CONSOLE_COLOR_RED
Vec3fX< details::Vec3Data< double > > Vector3d
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_...
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.
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Main namespace for MoveIt.
double distance(const urdf::Pose &transform)
A set of options for the kinematics solver.
Struct for containing jump_threshold.
Struct for containing max_step for computeCartesianPath.