39 #include <octomap_msgs/Octomap.h>
42 #include <kdl/frames_io.hpp>
59 KDL::Jacobian Jzero(_n);
61 Hessian Hzero = Hessian::Constant(6, Eigen::MatrixXd::Zero(_n, _n));
62 if (_flags &
KIN_J)
jacobian = ArrayJacobian::Constant(_size, Jzero);
63 if (_flags &
KIN_H)
hessian = ArrayHessian::Constant(_size, Hzero);
71 KinematicFrameRequest::KinematicFrameRequest(std::string _frame_A_link_name, KDL::Frame _frame_A_offset, std::string _frame_B_link_name, KDL::Frame _frame_B_offset) : frame_A_link_name(_frame_A_link_name), frame_A_offset(_frame_A_offset), frame_B_link_name(_frame_B_link_name), frame_B_offset(_frame_B_offset)
84 new (&
Phi) Eigen::Map<ArrayFrame>(solution->Phi.data() +
start,
length);
85 new (&
X) Eigen::Map<Eigen::VectorXd>(solution->x.data(), solution->x.rows());
103 if (!model)
ThrowPretty(
"No robot model provided!");
108 const robot_model::JointModelGroup* group = model->getJointModelGroup(joint_group);
111 auto names = model->getJointModelGroupNames();
114 if (!joint_group.empty())
116 std::stringstream ss;
117 ss <<
"Joint group '" << joint_group <<
"' not defined in the robot model. " << names.size() <<
" joint groups available";
118 if (names.size() >
static_cast<std::size_t
>(0))
121 for (
const auto& joint_group_name : names)
122 ss << joint_group_name <<
", ";
130 for (
auto joint_model : model->getActiveJointModels())
141 KDL::Tree robot_kinematics;
153 shapes_pub_ = Server::Advertise<visualization_msgs::MarkerArray>(
name_ + (
name_ ==
"" ?
"" :
"/") +
"CollisionShapes", 1,
true);
154 octomap_pub_ = Server::Advertise<octomap_msgs::Octomap>(
name_ + (
name_ ==
"" ?
"" :
"/") +
"OctoMap", 1,
true);
157 visualization_msgs::MarkerArray msg;
158 msg.markers.resize(1);
159 msg.markers[0].action = 3;
174 const robot_model::JointModel* root_joint =
model_->getRootJoint();
176 std::string world_frame_name;
179 if (
s.name_ == root_joint->getName())
181 world_frame_name =
s.parent_frame_;
185 if (world_frame_name.empty())
187 world_frame_name =
"world_frame";
188 WARNING_NAMED(
"KinematicTree",
"No virtual joint defined. Defaulting world frame to " << world_frame_name)
192 double root_mass = 0.0;
193 KDL::Vector root_cog = KDL::Vector::Zero();
194 auto& urdf_root_inertial =
model_->getURDF()->getRoot()->inertial;
195 if (urdf_root_inertial)
197 root_mass = urdf_root_inertial->mass;
198 root_cog = KDL::Vector(urdf_root_inertial->origin.position.x,
199 urdf_root_inertial->origin.position.y,
200 urdf_root_inertial->origin.position.z);
203 <<
" kg - CoG: " << root_cog);
207 KDL::RigidBodyInertia root_inertial(root_mass, root_cog);
210 model_tree_.push_back(std::make_shared<KinematicElement>(-1,
nullptr, KDL::Segment(world_frame_name, KDL::Joint(root_joint->getName(), KDL::Joint::None))));
219 const KDL::Joint::JointType types[] = {KDL::Joint::TransX, KDL::Joint::TransY, KDL::Joint::TransZ, KDL::Joint::RotZ, KDL::Joint::RotY, KDL::Joint::RotX};
220 const std::vector<std::string> floating_base_suffix = {
221 "/trans_x",
"/trans_y",
"/trans_z",
222 "/rot_z",
"/rot_y",
"/rot_x"};
223 for (
size_t i = 0; i < 6; ++i)
225 model_tree_[i + 1] = std::make_shared<KinematicElement>(i,
model_tree_[i], KDL::Segment(world_frame_name + floating_base_suffix[i], KDL::Joint(
root_joint_name_ + floating_base_suffix[i], types[i])));
245 const KDL::Joint::JointType types[] = {KDL::Joint::TransX, KDL::Joint::TransY,
247 for (
int i = 0; i < 3; ++i)
249 model_tree_[i + 1] = std::make_shared<KinematicElement>(
252 root_joint->getVariableNames()[i],
253 KDL::Joint(root_joint->getVariableNames()[i], types[i])));
259 ThrowPretty(
"Unsupported root joint type: " << root_joint->getTypeName());
285 for (
int i = 0; i <
tree_.size() - 1; ++i)
287 "Tree",
"Joint: " <<
tree_[i].lock()->segment.getJoint().getName() <<
" - Link: " <<
tree_[i].lock()->segment.getName()
288 <<
", parent: " <<
tree_[i].lock()->parent_name
289 <<
", mass: " <<
tree_[i].lock()->segment.getInertia().getMass()
290 <<
", CoM: " <<
tree_[i].lock()->segment.getInertia().getCOG());
298 for (std::shared_ptr<KinematicElement> Joint :
model_tree_)
300 Joint->is_robot_link =
true;
302 Joint->is_controlled = Joint->control_id >= 0;
305 if (Joint->is_controlled)
319 if (Joint->segment.getJoint().getName().find(
320 root_joint->getName()) != std::string::npos)
337 const urdf::ModelInterfaceSharedPtr&
urdf =
model_->getURDF();
338 std::vector<urdf::LinkSharedPtr> urdf_links;
339 urdf->getLinks(urdf_links);
342 for (urdf::LinkSharedPtr urdf_link : urdf_links)
344 if (urdf_link->parent_joint !=
nullptr && urdf_link->parent_joint->mimic !=
nullptr)
346 const auto& mimic = urdf_link->parent_joint->mimic;
347 if (
debug)
HIGHLIGHT(urdf_link->name <<
" is a mimic joint; mimicking " << mimic->joint_name <<
"; multiplier=" << mimic->multiplier <<
", offset=" << mimic->offset);
349 std::shared_ptr<KinematicElement> mimicked_element =
model_joints_map_[mimic->joint_name].lock();
350 std::shared_ptr<KinematicElement> element =
tree_map_[urdf_link->name].lock();
351 element->is_mimic_joint =
true;
352 element->mimic_multiplier = mimic->multiplier;
353 element->mimic_offset = mimic->offset;
354 element->mimic_joint_id = mimicked_element->id;
359 for (urdf::LinkSharedPtr urdf_link : urdf_links)
361 if (urdf_link->visual_array.size() > 0)
363 std::shared_ptr<KinematicElement> element =
tree_map_[urdf_link->name].lock();
365 element->visual.reserve(urdf_link->visual_array.size());
366 for (urdf::VisualSharedPtr urdf_visual : urdf_link->visual_array)
369 visual.
name = urdf_link->name +
"_visual_" + std::to_string(i);
370 visual.
frame = KDL::Frame(KDL::Rotation::Quaternion(urdf_visual->origin.rotation.x, urdf_visual->origin.rotation.y, urdf_visual->origin.rotation.z, urdf_visual->origin.rotation.w), KDL::Vector(urdf_visual->origin.position.x, urdf_visual->origin.position.y, urdf_visual->origin.position.z));
371 if (urdf_visual->material)
373 urdf::MaterialSharedPtr material = urdf_visual->material->name ==
"" ? urdf_visual->material :
urdf->getMaterial(urdf_visual->material->name);
374 visual.
color(0) = material->color.r;
375 visual.
color(1) = material->color.g;
376 visual.
color(2) = material->color.b;
377 visual.
color(3) = material->color.a;
385 switch (urdf_visual->geometry->type)
387 case urdf::Geometry::BOX:
389 std::shared_ptr<urdf::Box> box = std::static_pointer_cast<urdf::Box>(
ToStdPtr(urdf_visual->geometry));
390 visual.
shape = std::shared_ptr<shapes::Box>(
new shapes::Box(box->dim.x, box->dim.y, box->dim.z));
393 case urdf::Geometry::SPHERE:
395 std::shared_ptr<urdf::Sphere> sphere = std::static_pointer_cast<urdf::Sphere>(
ToStdPtr(urdf_visual->geometry));
399 case urdf::Geometry::CYLINDER:
401 std::shared_ptr<urdf::Cylinder> cylinder = std::static_pointer_cast<urdf::Cylinder>(
ToStdPtr(urdf_visual->geometry));
402 visual.
shape = std::shared_ptr<shapes::Cylinder>(
new shapes::Cylinder(cylinder->radius, cylinder->length));
405 case urdf::Geometry::MESH:
407 std::shared_ptr<urdf::Mesh> mesh = std::static_pointer_cast<urdf::Mesh>(
ToStdPtr(urdf_visual->geometry));
409 visual.
scale = Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z);
414 ThrowPretty(
"Unknown geometry type: " << urdf_visual->geometry->type);
416 element->visual.push_back(visual);
427 for (std::weak_ptr<KinematicElement> joint :
tree_)
429 tree_map_[joint.lock()->segment.getName()] = joint.lock();
448 visualization_msgs::Marker mrk;
457 std::shared_ptr<KinematicElement> child =
tree_map_.find(
name)->second.lock();
459 if (child->shape)
ThrowPretty(
"Can't re-attach collision shape without reattaching the object! ('" <<
name <<
"')");
460 std::shared_ptr<KinematicElement> parent;
461 if (parent_name ==
"")
469 parent =
tree_map_.find(parent_name)->second.lock();
471 if (parent->shape)
ThrowPretty(
"Can't attach object to a collision shape object! ('" << parent_name <<
"')");
474 child->segment = KDL::Segment(child->segment.getName(), child->segment.getJoint(), pose, child->segment.getInertia());
478 child->segment = KDL::Segment(child->segment.getName(), child->segment.getJoint(), parent->frame.Inverse() * child->frame * pose, child->segment.getInertia());
482 for (
auto it = child->parent.lock()->children.begin(); it != child->parent.lock()->children.end();)
484 std::shared_ptr<KinematicElement> childOfParent = it->lock();
485 if (childOfParent == child)
487 child->parent.lock()->children.erase(it);
495 child->parent = parent;
496 child->parent_name = parent->segment.getName();
497 parent->children.push_back(child);
498 child->UpdateClosestRobotLink();
502 std::shared_ptr<KinematicElement>
KinematicTree::AddEnvironmentElement(
const std::string& name,
const Eigen::Isometry3d& transform,
const std::string& parent,
shapes::ShapeConstPtr shape,
const KDL::RigidBodyInertia& inertia,
const Eigen::Vector4d& color,
const std::vector<VisualElement>& visual,
bool is_controlled)
504 std::shared_ptr<KinematicElement> element =
AddElement(
name,
transform, parent, shape, inertia, color, visual, is_controlled);
509 std::shared_ptr<KinematicElement>
KinematicTree::AddElement(
const std::string& name,
const Eigen::Isometry3d& transform,
const std::string& parent,
const std::string& shape_resource_path, Eigen::Vector3d scale,
const KDL::RigidBodyInertia& inertia,
const Eigen::Vector4d& color,
const std::vector<VisualElement>& visual,
bool is_controlled)
511 std::string shape_path(shape_resource_path);
512 if (shape_path.empty())
517 else if (shape_path.substr(0, 1) ==
"{")
519 shape_path =
"file://" +
ParsePath(shape_path);
522 else if (shape_path.substr(0, 10) ==
"package://" || shape_path.substr(0, 8) ==
"file:///")
531 std::shared_ptr<KinematicElement> element =
AddElement(
name,
transform, parent, shape, inertia, color, visual, is_controlled);
532 element->shape_resource_path = shape_path;
533 element->scale = scale;
537 std::shared_ptr<KinematicElement>
KinematicTree::AddElement(
const std::string& name,
const Eigen::Isometry3d& transform,
const std::string& parent,
shapes::ShapeConstPtr shape,
const KDL::RigidBodyInertia& inertia,
const Eigen::Vector4d& color,
const std::vector<VisualElement>& visual,
bool is_controlled)
539 std::shared_ptr<KinematicElement> parent_element;
542 parent_element =
root_;
547 for (
const auto& element :
tree_)
549 if (element.lock()->segment.getName() == parent)
551 parent_element = element.lock();
556 if (!found)
ThrowPretty(
"Can't find parent link named '" << parent <<
"'!");
558 KDL::Frame transform_kdl;
560 std::shared_ptr<KinematicElement> new_element = std::make_shared<KinematicElement>(
tree_.size(), parent_element, KDL::Segment(
name, KDL::Joint(KDL::Joint::None), transform_kdl, inertia));
563 new_element->shape = shape;
567 if (color != Eigen::Vector4d::Zero()) new_element->color = color;
569 new_element->parent_name = parent;
570 new_element->is_controlled = is_controlled;
571 tree_.push_back(new_element);
572 parent_element->children.push_back(new_element);
573 new_element->UpdateClosestRobotLink();
575 new_element->visual = visual;
582 std::shared_ptr<KinematicElement> new_element = std::make_shared<KinematicElement>(
model_tree_.size(), parent, segment->second.segment);
584 if (parent) parent->children.push_back(new_element);
585 for (KDL::SegmentMap::const_iterator child : segment->second.children)
604 auto element =
tree_map_[link_name].lock();
606 if (element && element->is_controlled)
608 return element->control_id;
613 element = element->parent.lock();
615 if (element && element->is_controlled)
617 return element->control_id;
621 catch (
const std::out_of_range& e)
636 for (
int i = 0; i < request.
frames.size(); ++i)
638 if (request.
frames[i].frame_A_link_name ==
"")
645 catch (
const std::out_of_range& e)
647 ThrowPretty(
"No frame_A link exists named '" << request.
frames[i].frame_A_link_name <<
"'");
649 if (request.
frames[i].frame_B_link_name ==
"")
656 catch (
const std::out_of_range& e)
658 ThrowPretty(
"No frame_B link exists named '" << request.
frames[i].frame_B_link_name <<
"'");
697 std::queue<std::shared_ptr<KinematicElement>> elements;
698 elements.push(
root_);
699 root_->RemoveExpiredChildren();
700 while (elements.size() > 0)
702 auto element = elements.front();
706 if (element->id > -1)
708 if (element->segment.getJoint().getType() != KDL::Joint::JointType::None)
710 if (!element->is_mimic_joint)
712 element->frame = element->parent.lock()->frame * element->GetPose(
tree_state_(element->id));
716 element->frame = element->parent.lock()->frame * element->GetPose(
tree_state_(element->mimic_joint_id));
721 element->frame = element->parent.lock()->frame * element->GetPose();
729 element->frame = element->GetPose();
731 element->RemoveExpiredChildren();
732 for (std::weak_ptr<KinematicElement> child : element->children)
734 elements.push(child.lock());
748 for (std::weak_ptr<KinematicElement> element :
tree_)
774 for (
int i = 0; i <
tree_.size(); ++i)
777 if (
tree_[i].lock()->shape_resource_path !=
"")
779 visualization_msgs::Marker mrk;
780 mrk.action = visualization_msgs::Marker::ADD;
781 mrk.frame_locked =
true;
783 mrk.ns =
"CollisionObjects";
785 mrk.header.frame_id = tf_prefix +
"/" +
tree_[i].lock()->segment.getName();
786 mrk.pose.orientation.w = 1.0;
787 mrk.type = visualization_msgs::Marker::MESH_RESOURCE;
788 mrk.mesh_resource =
tree_[i].lock()->shape_resource_path;
789 mrk.mesh_use_embedded_materials =
true;
790 mrk.scale.x =
tree_[i].lock()->scale(0);
791 mrk.scale.y =
tree_[i].lock()->scale(1);
792 mrk.scale.z =
tree_[i].lock()->scale(2);
796 else if (
tree_[i].lock()->shape && (!
tree_[i].lock()->closest_robot_link.lock() || !
tree_[i].lock()->closest_robot_link.lock()->is_robot_link))
798 if (
tree_[i].lock()->shape->type != shapes::ShapeType::OCTREE)
800 visualization_msgs::Marker mrk;
802 mrk.action = visualization_msgs::Marker::ADD;
803 mrk.frame_locked =
true;
805 mrk.ns =
"CollisionObjects";
807 mrk.header.frame_id = tf_prefix +
"/" +
tree_[i].lock()->segment.getName();
808 mrk.pose.orientation.w = 1.0;
816 octomap::OcTree my_octomap = *std::static_pointer_cast<const shapes::OcTree>(
tree_[i].lock()->shape)->octree.get();
817 octomap_msgs::Octomap octomap_msg;
819 octomap_msg.header.frame_id = tf_prefix +
"/" +
tree_[i].lock()->segment.getName();
837 KDL::Frame
KinematicTree::FK(std::shared_ptr<KinematicElement> element_A,
const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B,
const KDL::Frame& offset_b)
const
839 if (!element_A)
ThrowPretty(
"The pointer to KinematicElement A is dead.");
842 frame.
frame_B = (element_B ==
nullptr) ?
root_ : element_B;
848 KDL::Frame
KinematicTree::FK(
const std::string& element_A,
const KDL::Frame& offset_a,
const std::string& element_B,
const KDL::Frame& offset_b)
const
850 std::string name_a = element_A ==
"" ?
root_->segment.getName() : element_A;
851 std::string name_b = element_B ==
"" ?
root_->segment.getName() : element_B;
856 return FK(
A->second.lock(), offset_a, B->second.lock(), offset_b);
869 Eigen::MatrixXd
KinematicTree::Jacobian(std::shared_ptr<KinematicElement> element_A,
const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B,
const KDL::Frame& offset_b)
const
871 if (!element_A)
ThrowPretty(
"The pointer to KinematicElement A is dead.");
874 frame.
frame_B = (element_B ==
nullptr) ?
root_ : element_B;
882 Eigen::MatrixXd
KinematicTree::Jacobian(
const std::string& element_A,
const KDL::Frame& offset_a,
const std::string& element_B,
const KDL::Frame& offset_b)
const
884 std::string name_a = element_A ==
"" ?
root_->segment.getName() : element_A;
885 std::string name_b = element_B ==
"" ?
root_->segment.getName() : element_B;
890 return Jacobian(
A->second.lock(), offset_a, B->second.lock(), offset_b);
895 if (!element_A)
ThrowPretty(
"The pointer to KinematicElement A is dead.");
898 frame.
frame_B = (element_B ==
nullptr) ?
root_ : element_B;
910 std::string name_a = element_A ==
"" ?
root_->segment.getName() : element_A;
911 std::string name_b = element_B ==
"" ?
root_->segment.getName() : element_B;
916 return this->
Hessian(
A->second.lock(), offset_a, B->second.lock(), offset_b);
921 jacobian.data.setZero();
923 std::shared_ptr<KinematicElement> it = frame.
frame_A.lock();
924 while (it !=
nullptr)
926 if (it->is_controlled)
928 KDL::Frame segment_reference;
929 if (it->parent.lock() !=
nullptr) segment_reference = it->parent.lock()->frame;
930 jacobian.setColumn(it->control_id, frame.
temp_B.M.Inverse() * (segment_reference.M * it->segment.twist(
tree_state_(it->id), 1.0)).RefPoint(frame.
temp_A.p - it->frame.p));
932 it = it->parent.lock();
935 while (it !=
nullptr)
937 if (it->is_controlled)
939 KDL::Frame segment_reference;
940 if (it->parent.lock() !=
nullptr) segment_reference = it->parent.lock()->frame;
941 jacobian.setColumn(it->control_id, jacobian.getColumn(it->control_id) - (frame.
temp_B.M.Inverse() * (segment_reference.M * it->segment.twist(
tree_state_(it->id), 1.0)).RefPoint(frame.
temp_A.p - it->frame.p)));
943 it = it->parent.lock();
949 hessian.conservativeResize(6);
950 for (
int i = 0; i < 6; ++i)
952 hessian(i).resize(jacobian.columns(), jacobian.columns());
953 hessian(i).setZero();
958 for (
int i = 0; i < jacobian.columns(); ++i)
960 axis.rot = jacobian.getColumn(i).rot;
961 for (
int j = i; j < jacobian.columns(); ++j)
963 KDL::Twist Hij = axis * jacobian.getColumn(j);
964 hessian(0)(i, j) = Hij[0];
965 hessian(1)(i, j) = Hij[1];
966 hessian(2)(i, j) = Hij[2];
967 hessian(0)(j, i) = Hij[0];
968 hessian(1)(j, i) = Hij[1];
969 hessian(2)(j, i) = Hij[2];
972 hessian(3)(j, i) = Hij[3];
973 hessian(4)(j, i) = Hij[4];
974 hessian(5)(j, i) = Hij[5];
1012 std::map<std::string, std::vector<double>> limits;
1015 limits[it.lock()->segment.getJoint().getName()] = it.lock()->joint_limits;
1078 else if (velocity_in.rows() == 1)
1104 else if (acceleration_in.rows() == 1)
1122 const std::vector<double>& lower,
const std::vector<double>& upper)
1128 if (lower.size() != 6 || upper.size() != 6)
1132 for (
int i = 0; i < 6; ++i)
1141 const std::vector<double>& lower,
const std::vector<double>& upper,
const std::vector<double>& velocity,
const std::vector<double>& acceleration)
1147 if (lower.size() != 6 || upper.size() != 6)
1151 if (velocity.size() != 6 && velocity.size() != 0)
1155 if (acceleration.size() != 6 && acceleration.size() != 0)
1159 for (
int i = 0; i < 6; ++i)
1163 controlled_joints_[i].lock()->acceleration_limit = {acceleration.size() != 0 ? acceleration[i] :
inf};
1170 const std::vector<double>& lower,
const std::vector<double>& upper)
1176 if (lower.size() != 3 || upper.size() != 3)
1180 for (
int i = 0; i < 3; ++i)
1189 const std::vector<double>& lower,
const std::vector<double>& upper,
const std::vector<double>& velocity,
const std::vector<double>& acceleration)
1195 if (lower.size() != 3 || upper.size() != 3)
1199 if (velocity.size() != 3 && velocity.size() != 0)
1203 if (acceleration.size() != 3 && acceleration.size() != 0)
1207 for (
int i = 0; i < 3; ++i)
1211 controlled_joints_[i].lock()->acceleration_limit = {acceleration.size() != 0 ? acceleration[i] :
inf};
1219 std::vector<std::string> vars =
model_->getVariableNames();
1220 for (
int i = 0; i < vars.size(); ++i)
1225 int index = ControlledJoint.lock()->control_id;
1231 if (
model_->getVariableBounds(vars[i]).position_bounded_)
1239 if (
model_->getVariableBounds(vars[i]).velocity_bounded_)
1247 if (
model_->getVariableBounds(vars[i]).acceleration_bounded_)
1301 return root_->segment.getName();
1322 std::map<std::string, double> ret;
1333 for (
const std::string& l : {begin, end})
1342 std::vector<std::string> chain;
1343 for (std::weak_ptr<KinematicElement> l =
tree_map_.at(end);
1344 l.lock()->segment.getName() != begin;
1345 l = l.lock()->parent, chain.push_back(l.lock()->segment.getJoint().getName()))
1347 if (l.lock()->parent.lock() ==
nullptr)
1349 ThrowPretty(
"There is no connection between '" + begin +
"' and '" + end +
"'!");
1354 std::reverse(chain.begin(), chain.end());
1361 for (
const std::string& l : {begin, end})
1370 std::vector<std::string> chain;
1371 for (std::shared_ptr<const KinematicElement> l =
tree_map_.at(end).lock(); l->segment.getName() != begin; l = l->parent.lock())
1373 chain.push_back(l->segment.getName());
1374 if (l->parent.lock() ==
nullptr)
1376 ThrowPretty(
"There is no connection between '" + begin +
"' and '" + end +
"'!");
1381 std::reverse(chain.begin(), chain.end());
1409 for (
auto& joint :
x)
1415 catch (
const std::out_of_range& e)
1417 WARNING(
"Robot model does not contain joint '" << joint.first <<
"' - ignoring.");
1453 std::map<std::string, shapes::ShapeType> ret;
1456 ret[element.second.lock()->segment.getName()] = element.second.lock()->shape->type;
1472 return it->second.lock();