rep_factory.cpp
Go to the documentation of this file.
1 
31 
32 #include <console_bridge/console.h>
33 
34 namespace tesseract_kinematics
35 {
36 std::unique_ptr<InverseKinematics> REPInvKinFactory::create(const std::string& solver_name,
37  const tesseract_scene_graph::SceneGraph& scene_graph,
38  const tesseract_scene_graph::SceneState& scene_state,
39  const KinematicsPluginFactory& plugin_factory,
40  const YAML::Node& config) const
41 {
44  double m_reach{ 0 };
45  Eigen::MatrixX2d sample_range;
46  Eigen::VectorXd sample_res;
47 
48  try
49  {
50  // Get Reach
51  if (YAML::Node n = config["manipulator_reach"])
52  m_reach = n.as<double>();
53  else
54  throw std::runtime_error("REPInvKinFactory, missing 'manipulator_reach' entry!");
55 
56  // Get positioner sample resolution
57  std::map<std::string, std::array<double, 3>> sample_res_map;
58  if (YAML::Node sample_res_node = config["positioner_sample_resolution"])
59  {
60  for (auto it = sample_res_node.begin(); it != sample_res_node.end(); ++it)
61  {
62  const YAML::Node& joint = *it;
63  std::array<double, 3> values{ 0, 0, 0 };
64 
65  std::string joint_name;
66  if (YAML::Node n = joint["name"])
67  joint_name = n.as<std::string>();
68  else
69  throw std::runtime_error("REPInvKinFactory, 'positioner_sample_resolution' missing 'name' entry!");
70 
71  if (YAML::Node n = joint["value"])
72  values[0] = n.as<double>();
73  else
74  throw std::runtime_error("REPInvKinFactory, 'positioner_sample_resolution' missing 'value' entry!");
75 
76  auto jnt = scene_graph.getJoint(joint_name);
77  if (jnt == nullptr)
78  throw std::runtime_error("REPInvKinFactory, 'positioner_sample_resolution' failed to find joint in scene "
79  "graph!");
80 
81  values[1] = jnt->limits->lower;
82  values[2] = jnt->limits->upper;
83 
84  if (YAML::Node min = joint["min"])
85  values[1] = min.as<double>();
86 
87  if (YAML::Node max = joint["max"])
88  values[2] = max.as<double>();
89 
90  if (values[1] < jnt->limits->lower)
91  throw std::runtime_error("REPInvKinFactory, sample range minimum is less than joint minimum!");
92 
93  if (values[2] > jnt->limits->upper)
94  throw std::runtime_error("REPInvKinFactory, sample range maximum is greater than joint maximum!");
95 
96  if (values[1] > values[2])
97  throw std::runtime_error("REPInvKinFactory, sample range is not valid!");
98 
99  sample_res_map[joint_name] = values;
100  }
101  }
102  else
103  {
104  throw std::runtime_error("REPInvKinFactory, missing 'positioner_sample_resolution' entry!");
105  }
106 
107  // Get Positioner
108  if (YAML::Node positioner = config["positioner"])
109  {
111  if (YAML::Node n = positioner["class"])
112  p_info.class_name = n.as<std::string>();
113  else
114  throw std::runtime_error("REPInvKinFactory, 'positioner' missing 'class' entry!");
115 
116  if (YAML::Node n = positioner["config"])
117  p_info.config = n;
118 
119  fwd_kin = plugin_factory.createFwdKin(p_info.class_name, p_info, scene_graph, scene_state);
120  if (fwd_kin == nullptr)
121  throw std::runtime_error("REPInvKinFactory, failed to create positioner forward kinematics!");
122 
123  if (sample_res_map.size() != static_cast<std::size_t>(fwd_kin->numJoints()))
124  throw std::runtime_error("REPInvKinFactory, positioner sample resolution has incorrect number of joints!");
125  }
126  else
127  {
128  throw std::runtime_error("REPInvKinFactory, missing 'positioner' entry!");
129  }
130 
131  // Load Positioner Resolution and Range
132  sample_range.resize(fwd_kin->numJoints(), 2);
133  sample_res.resize(fwd_kin->numJoints());
134  std::vector<std::string> joint_names = fwd_kin->getJointNames();
135  for (Eigen::Index i = 0; i < static_cast<Eigen::Index>(joint_names.size()); ++i)
136  {
137  const auto& jn = joint_names[static_cast<std::size_t>(i)];
138  auto it = sample_res_map.find(jn);
139  if (it == sample_res_map.end())
140  throw std::runtime_error("REPInvKinFactory, positioner sample resolution missing joint '" + jn + "'!");
141 
142  sample_res(i) = it->second[0];
143  sample_range(i, 0) = it->second[1];
144  sample_range(i, 1) = it->second[2];
145  }
146 
147  // Get Manipulator
148  if (YAML::Node manipulator = config["manipulator"])
149  {
151  if (YAML::Node n = manipulator["class"])
152  m_info.class_name = n.as<std::string>();
153  else
154  throw std::runtime_error("REPInvKinFactory, 'manipulator' missing 'class' entry!");
155 
156  if (YAML::Node n = manipulator["config"])
157  m_info.config = n;
158 
159  inv_kin = plugin_factory.createInvKin(m_info.class_name, m_info, scene_graph, scene_state);
160  if (inv_kin == nullptr)
161  throw std::runtime_error("REPInvKinFactory, failed to create positioner inverse kinematics!");
162  }
163  else
164  {
165  throw std::runtime_error("REPInvKinFactory, missing 'manipulator' entry!");
166  }
167  }
168  catch (const std::exception& e)
169  {
170  CONSOLE_BRIDGE_logError("REPInvKinFactory: Failed to parse yaml config data! Details: %s", e.what());
171  return nullptr;
172  }
173 
174  return std::make_unique<REPInvKin>(
175  scene_graph, scene_state, std::move(inv_kin), m_reach, std::move(fwd_kin), sample_range, sample_res, solver_name);
176 }
177 
178 PLUGIN_ANCHOR_IMPL(REPInvKinFactoriesAnchor)
179 
180 } // namespace tesseract_kinematics
181 
182 // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
graph.h
tesseract_kinematics::REPInvKinFactory::create
std::unique_ptr< InverseKinematics > create(const std::string &solver_name, const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, const KinematicsPluginFactory &plugin_factory, const YAML::Node &config) const override final
Create Inverse Kinematics Object.
Definition: rep_factory.cpp:36
rep_inv_kin.h
tesseract_kinematics::REPInvKinFactory
Definition: rep_factory.h:34
joint.h
tesseract_scene_graph::SceneGraph
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
tesseract_scene_graph::SceneState
tesseract_common::PluginInfo::class_name
std::string class_name
tesseract_common::PluginInfo
tesseract_kinematics::KinematicsPluginFactory::createInvKin
std::unique_ptr< InverseKinematics > createInvKin(const std::string &group_name, const std::string &solver_name, const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state) const
Get inverse kinematics object given group name and solver name.
Definition: kinematics_plugin_factory.cpp:290
TESSERACT_ADD_INV_KIN_PLUGIN
TESSERACT_ADD_INV_KIN_PLUGIN(tesseract_kinematics::REPInvKinFactory, REPInvKinFactory)
rep_factory.h
Robot with External Positioner Inverse kinematics Factory.
forward_kinematics.h
Forward kinematics functions.
tesseract_common::PluginInfo::config
YAML::Node config
tesseract_kinematics::KinematicsPluginFactory::createFwdKin
std::unique_ptr< ForwardKinematics > createFwdKin(const std::string &group_name, const std::string &solver_name, const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state) const
Get forward kinematics object given group name and solver name.
Definition: kinematics_plugin_factory.cpp:233
tesseract_scene_graph::SceneGraph::getJoint
std::shared_ptr< const Joint > getJoint(const std::string &name) const
tesseract_kinematics::ForwardKinematics::UPtr
std::unique_ptr< ForwardKinematics > UPtr
Definition: forward_kinematics.h:52
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::KinematicsPluginFactory
Definition: kinematics_plugin_factory.h:116


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14