34 #include <console_bridge/console.h>
35 #include <boost/graph/depth_first_search.hpp>
58 template <
class u,
class g>
62 auto num_in_edges =
static_cast<int>(boost::in_degree(vertex, graph));
63 if (num_in_edges == 0)
66 boost::graph_traits<tesseract_scene_graph::Graph>::in_edge_iterator ei, ei_end;
67 boost::tie(ei, ei_end) = boost::in_edges(vertex, graph);
70 std::string joint_name =
prefix_ + joint->getName();
71 std::string parent_link_name =
prefix_ + joint->parent_link_name;
72 std::string child_link_name =
prefix_ + joint->child_link_name;
90 auto n = std::make_unique<OFKTFixedNode>(
91 parent_node, child->
getLinkName(), child->getJointName(), child->getStaticTransformation());
92 cloned.
link_map_[child->getLinkName()] = n.get();
94 cloned.
nodes_[child->getJointName()] = std::move(n);
98 auto n = std::make_unique<OFKTFloatingNode>(
99 parent_node, child->
getLinkName(), child->getJointName(), child->getStaticTransformation());
100 cloned.
link_map_[child->getLinkName()] = n.get();
102 cloned.
nodes_[child->getJointName()] = std::move(n);
108 auto n = std::make_unique<OFKTRevoluteNode>(
109 parent_node, cn->
getLinkName(), cn->getJointName(), cn->getStaticTransformation(), cn->getAxis());
110 n->local_tf_ = cn->getLocalTransformation();
111 n->world_tf_ = cn->getWorldTransformation();
112 n->joint_value_ = cn->getJointValue();
114 cloned.
link_map_[cn->getLinkName()] = n.get();
116 cloned.
nodes_[cn->getJointName()] = std::move(n);
122 auto n = std::make_unique<OFKTContinuousNode>(
123 parent_node, cn->
getLinkName(), cn->getJointName(), cn->getStaticTransformation(), cn->getAxis());
124 n->local_tf_ = cn->getLocalTransformation();
125 n->world_tf_ = cn->getWorldTransformation();
126 n->joint_value_ = cn->getJointValue();
128 cloned.
link_map_[cn->getLinkName()] = n.get();
130 cloned.
nodes_[cn->getJointName()] = std::move(n);
136 auto n = std::make_unique<OFKTPrismaticNode>(
137 parent_node, cn->
getLinkName(), cn->getJointName(), cn->getStaticTransformation(), cn->getAxis());
138 n->local_tf_ = cn->getLocalTransformation();
139 n->world_tf_ = cn->getWorldTransformation();
140 n->joint_value_ = cn->getJointValue();
142 cloned.
link_map_[cn->getLinkName()] = n.get();
144 cloned.
nodes_[cn->getJointName()] = std::move(n);
148 throw std::runtime_error(
"Unsupported OFKTNode type!");
162 root_ = std::make_unique<OFKTRootNode>(root_name);
177 root_ = std::make_unique<OFKTRootNode>(other.
root_->getLinkName());
187 std::shared_lock<std::shared_mutex> lock(
mutex_);
188 return std::make_unique<OFKTStateSolver>(*
this);
193 std::unique_lock<std::shared_mutex> lock(
mutex_);
199 std::shared_lock<std::shared_mutex> lock(
mutex_);
205 std::unique_lock<std::shared_mutex> lock(
mutex_);
221 std::unique_lock<std::shared_mutex> lock(
mutex_);
229 for (
const auto& floating_joint_value : floating_joint_values)
232 nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
241 std::unique_lock<std::shared_mutex> lock(
mutex_);
243 for (
const auto& joint : joint_values)
245 nodes_[joint.first]->storeJointValue(joint.second);
249 for (
const auto& floating_joint_value : floating_joint_values)
252 nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
259 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
262 std::unique_lock<std::shared_mutex> lock(
mutex_);
263 assert(joint_names.size() ==
static_cast<std::size_t
>(joint_values.size()));
264 Eigen::VectorXd jv = joint_values;
265 for (std::size_t i = 0; i < joint_names.size(); ++i)
267 nodes_[joint_names[i]]->storeJointValue(joint_values(
static_cast<long>(i)));
271 for (
const auto& floating_joint_value : floating_joint_values)
274 nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
282 std::unique_lock<std::shared_mutex> lock(
mutex_);
283 for (
const auto& floating_joint_value : floating_joint_values)
286 nodes_[floating_joint_value.first]->setStaticTransformation(floating_joint_value.second);
295 std::shared_lock<std::shared_mutex> lock(
mutex_);
301 for (
const auto& floating_joint_value : floating_joint_values)
302 state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
304 update(state,
root_.get(), Eigen::Isometry3d::Identity(),
false);
312 for (
const auto& joint : joint_values)
313 state.joints[joint.first] = joint.second;
315 for (
const auto& floating_joint_value : floating_joint_values)
316 state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
318 update(state,
root_.get(), Eigen::Isometry3d::Identity(),
false);
323 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
326 std::shared_lock<std::shared_mutex> lock(
mutex_);
327 assert(
static_cast<Eigen::Index
>(joint_names.size()) == joint_values.size());
329 for (std::size_t i = 0; i < joint_names.size(); ++i)
330 state.joints[joint_names[i]] = joint_values[
static_cast<long>(i)];
332 for (
const auto& floating_joint_value : floating_joint_values)
333 state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
335 update(state,
root_.get(), Eigen::Isometry3d::Identity(),
false);
341 std::shared_lock<std::shared_mutex> lock(
mutex_);
343 for (
const auto& floating_joint_value : floating_joint_values)
344 state.floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
346 update(state,
root_.get(), Eigen::Isometry3d::Identity(),
false);
352 std::shared_lock<std::shared_mutex> lock(
mutex_);
358 std::shared_lock<std::shared_mutex> lock(
mutex_);
363 const std::string& link_name,
366 std::shared_lock<std::shared_mutex> lock(
mutex_);
368 for (Eigen::Index i = 0; i < joint_values.rows(); ++i)
372 for (
const auto& floating_joint_value : floating_joint_values)
373 floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
379 const std::string& link_name,
382 std::shared_lock<std::shared_mutex> lock(
mutex_);
384 for (
const auto& joint : joints_values)
385 joints[joint.first] = joint.second;
388 for (
const auto& floating_joint_value : floating_joint_values)
389 floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
395 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
396 const std::string& link_name,
399 std::shared_lock<std::shared_mutex> lock(
mutex_);
401 for (Eigen::Index i = 0; i < joint_values.rows(); ++i)
402 joints[joint_names[
static_cast<std::size_t
>(i)]] = joint_values[i];
405 for (
const auto& floating_joint_value : floating_joint_values)
406 floating_joints.at(floating_joint_value.first) = floating_joint_value.second;
412 const std::string& link_name,
416 Eigen::MatrixXd jacobian = Eigen::MatrixXd::Zero(6,
static_cast<Eigen::Index
>(
active_joint_names_.size()));
418 Eigen::Isometry3d total_tf{ Eigen::Isometry3d::Identity() };
419 while (node !=
root_.get())
427 total_tf = floating_joint_values.at(node->
getJointName()) * total_tf;
432 total_tf = local_tf * total_tf;
440 jacobian.col(idx) = twist;
452 std::shared_lock<std::shared_mutex> lock(
mutex_);
458 std::shared_lock<std::shared_mutex> lock(
mutex_);
464 std::shared_lock<std::shared_mutex> lock(
mutex_);
470 std::shared_lock<std::shared_mutex> lock(
mutex_);
471 return root_->getLinkName();
476 std::shared_lock<std::shared_mutex> lock(
mutex_);
482 std::shared_lock<std::shared_mutex> lock(
mutex_);
483 std::vector<std::string> link_names;
484 link_names.reserve(
nodes_.size());
491 std::shared_lock<std::shared_mutex> lock(
mutex_);
492 std::vector<std::string> link_names;
493 link_names.reserve(
nodes_.size());
500 std::shared_lock<std::shared_mutex> lock(
mutex_);
502 return (std::find(active_link_names.begin(), active_link_names.end(), link_name) != active_link_names.end());
507 std::shared_lock<std::shared_mutex> lock(
mutex_);
527 const std::string& to_link_name)
const
534 std::shared_lock<std::shared_mutex> lock(
mutex_);
540 std::unique_lock<std::shared_mutex> lock(
mutex_);
551 std::vector<JointLimits::ConstPtr> new_joint_limits;
567 std::unique_lock<std::shared_mutex> lock(
mutex_);
571 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to replace joint '%s' which does not exist!",
578 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to replace joint '%s' with parent link name that does not exist!",
585 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to replace joint '%s' with different child link name!",
590 std::vector<JointLimits::ConstPtr> new_joint_limits;
601 std::unique_lock<std::shared_mutex> lock(
mutex_);
605 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to link '%s' that does not exist!", joint.
child_link_name.c_str());
611 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to move link to parent link '%s' that does not exist!",
616 std::vector<JointLimits::ConstPtr> new_joint_limits;
627 std::unique_lock<std::shared_mutex> lock(
mutex_);
631 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to remove link '%s' which does not exist!", name.c_str());
635 std::vector<std::string> removed_links;
636 removed_links.reserve(
nodes_.size());
638 std::vector<std::string> removed_joints;
639 removed_joints.reserve(
nodes_.size());
641 std::vector<std::string> removed_active_joints;
642 removed_active_joints.reserve(
nodes_.size());
644 std::vector<long> removed_active_joints_indices;
645 removed_active_joints_indices.reserve(
nodes_.size());
647 removeNode(it->second, removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
650 removeJointHelper(removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
659 std::unique_lock<std::shared_mutex> lock(
mutex_);
660 auto it =
nodes_.find(name);
663 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to remove joint '%s' which does not exist!", name.c_str());
667 std::vector<std::string> removed_links;
668 removed_links.reserve(
nodes_.size());
670 std::vector<std::string> removed_joints;
671 removed_joints.reserve(
nodes_.size());
673 std::vector<std::string> removed_active_joints;
674 removed_active_joints.reserve(
nodes_.size());
676 std::vector<long> removed_active_joints_indices;
677 removed_active_joints_indices.reserve(
nodes_.size());
679 removeNode(it->second.get(), removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
682 removeJointHelper(removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
691 std::unique_lock<std::shared_mutex> lock(
mutex_);
692 auto it =
nodes_.find(name);
695 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to move joint '%s' which does not exist!", name.c_str());
701 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to move joint '%s' to parent link '%s' which does not exist!",
703 parent_link.c_str());
707 auto& n = it->second;
708 n->getParent()->removeChild(n.get());
710 n->setParent(new_parent);
720 std::unique_lock<std::shared_mutex> lock(
mutex_);
721 auto it =
nodes_.find(name);
724 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to change joint '%s' origin which does not exist!", name.c_str());
728 it->second->setStaticTransformation(new_origin);
739 std::unique_lock<std::shared_mutex> lock(
mutex_);
740 auto it =
nodes_.find(name);
743 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
757 std::unique_lock<std::shared_mutex> lock(
mutex_);
758 auto it =
nodes_.find(name);
761 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
775 std::unique_lock<std::shared_mutex> lock(
mutex_);
776 auto it =
nodes_.find(name);
779 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
793 std::unique_lock<std::shared_mutex> lock(
mutex_);
794 auto it =
nodes_.find(name);
797 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, tried to change joint '%s' positioner limits which does not exist!",
811 std::unique_lock<std::shared_mutex> lock(
mutex_);
812 if (
root_ ==
nullptr)
820 child_link.erase(0, prefix.length());
824 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, Failed to add inserted graph, provided joint link names do not exist in "
831 CONSOLE_BRIDGE_logError(
"OFKTStateSolver, Failed to add inserted graph, provided joint name %s already exists!",
836 std::vector<JointLimits::ConstPtr> new_joints_limits;
837 new_joints_limits.reserve(boost::num_edges(scene_graph));
843 std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t> index_map;
844 boost::associative_property_map<std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t>> prop_index_map(
848 tesseract_scene_graph::Graph::vertex_iterator i, iend;
849 for (boost::tie(i, iend) = boost::vertices(scene_graph); i != iend; ++i, ++c)
850 boost::put(prop_index_map, *i, c);
853 boost::visitor(builder)
855 .vertex_index_map(prop_index_map));
908 update_required =
true;
912 update_required =
true;
922 update(child, update_required);
927 const Eigen::Isometry3d& parent_world_tf,
928 bool update_required)
const
930 Eigen::Isometry3d updated_parent_world_tf{ Eigen::Isometry3d::Identity() };
938 updated_parent_world_tf = parent_world_tf * tf;
940 update_required =
true;
948 update_required =
true;
963 update(state, child, updated_parent_world_tf, update_required);
973 assert(scene_graph.
isTree());
975 const std::string& root_name = prefix + scene_graph.
getRoot();
977 root_ = std::make_unique<OFKTRootNode>(root_name);
982 std::vector<JointLimits::ConstPtr> new_joints_limits;
983 new_joints_limits.reserve(scene_graph.
getJoints().size());
986 std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t> index_map;
987 boost::associative_property_map<std::map<tesseract_scene_graph::SceneGraph::Vertex, size_t>> prop_index_map(
991 tesseract_scene_graph::Graph::vertex_iterator i, iend;
992 for (boost::tie(i, iend) = boost::vertices(scene_graph); i != iend; ++i, ++c)
993 boost::put(prop_index_map, *i, c);
995 boost::depth_first_search(
997 boost::visitor(builder).root_vertex(scene_graph.
getVertex(root_name)).vertex_index_map(prop_index_map));
1012 const std::string old_joint_name = old_node->getJointName();
1013 old_node->getParent()->removeChild(old_node);
1016 std::vector<std::string> removed_links;
1019 std::vector<std::string> removed_joints;
1020 std::vector<std::string> removed_active_joints;
1021 std::vector<long> removed_active_joints_indices;
1022 removed_joints.push_back(old_joint_name);
1025 removed_active_joints.push_back(old_joint_name);
1030 std::vector<OFKTNode*> children = old_node->getChildren();
1033 nodes_.erase(old_joint_name);
1034 removeJointHelper(removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
1044 for (
auto* child : children)
1046 replaced_node->addChild(child);
1047 child->setParent(replaced_node.get());
1050 update(replaced_node.get(),
true);
1060 n->getParent()->removeChild(n.get());
1066 n->setParent(new_parent);
1076 const std::vector<std::string>& removed_joints,
1077 const std::vector<std::string>& removed_active_joints,
1078 const std::vector<long>& removed_active_joints_indices)
1080 if (!removed_links.empty())
1084 [removed_links](
const std::string& link_name) {
1085 return (std::find(removed_links.begin(), removed_links.end(), link_name) !=
1086 removed_links.end());
1091 if (!removed_joints.empty())
1095 [removed_joints](
const std::string& joint_name) {
1096 return (std::find(removed_joints.begin(), removed_joints.end(), joint_name) !=
1097 removed_joints.end());
1103 [removed_joints](
const std::string& joint_name) {
1104 return (std::find(removed_joints.begin(),
1105 removed_joints.end(),
1106 joint_name) != removed_joints.end());
1111 if (!removed_active_joints.empty())
1115 [removed_active_joints](
const std::string& joint_name) {
1116 return (std::find(removed_active_joints.begin(),
1117 removed_active_joints.end(),
1118 joint_name) != removed_active_joints.end());
1131 if (std::find(removed_active_joints_indices.begin(), removed_active_joints_indices.end(), i) ==
1132 removed_active_joints_indices.end())
1147 const std::string& joint_name,
1148 const std::string& parent_link_name,
1149 const std::string& child_link_name,
1150 std::vector<std::shared_ptr<const JointLimits>>& new_joint_limits)
1157 assert(parent_node !=
nullptr);
1158 auto n = std::make_unique<OFKTFixedNode>(
1166 nodes_[joint_name] = std::move(n);
1172 assert(parent_node !=
nullptr);
1173 auto n = std::make_unique<OFKTRevoluteNode>(
1183 new_joint_limits.push_back(joint.
limits);
1184 nodes_[joint_name] = std::move(n);
1190 assert(parent_node !=
nullptr);
1191 auto n = std::make_unique<OFKTContinuousNode>(
1201 new_joint_limits.push_back(joint.
limits);
1202 nodes_[joint_name] = std::move(n);
1208 assert(parent_node !=
nullptr);
1209 auto n = std::make_unique<OFKTPrismaticNode>(
1219 new_joint_limits.push_back(joint.
limits);
1220 nodes_[joint_name] = std::move(n);
1226 assert(parent_node !=
nullptr);
1227 auto n = std::make_unique<OFKTFloatingNode>(
1237 nodes_[joint_name] = std::move(n);
1243 throw std::runtime_error(
"Unsupported joint type for joint '" + joint_name +
"'");
1250 std::vector<std::string>& removed_links,
1251 std::vector<std::string>& removed_joints,
1252 std::vector<std::string>& removed_active_joints,
1253 std::vector<long>& removed_active_joints_indices)
1270 std::vector<OFKTNode*> children = node->
getChildren();
1271 for (
auto* child : children)
1272 removeNode(child, removed_links, removed_joints, removed_active_joints, removed_active_joints_indices);
1284 if (!new_joint_limits.empty())
1299 for (
const auto& limits : new_joint_limits)