32 #include <console_bridge/console.h>
40 const YAML::Node& config)
const
45 Eigen::MatrixX2d sample_range;
46 Eigen::VectorXd sample_res;
51 if (YAML::Node n = config[
"manipulator_reach"])
52 m_reach = n.as<
double>();
54 throw std::runtime_error(
"REPInvKinFactory, missing 'manipulator_reach' entry!");
57 std::map<std::string, std::array<double, 3>> sample_res_map;
58 if (YAML::Node sample_res_node = config[
"positioner_sample_resolution"])
60 for (
auto it = sample_res_node.begin(); it != sample_res_node.end(); ++it)
62 const YAML::Node& joint = *it;
63 std::array<double, 3> values{ 0, 0, 0 };
65 std::string joint_name;
66 if (YAML::Node n = joint[
"name"])
67 joint_name = n.as<std::string>();
69 throw std::runtime_error(
"REPInvKinFactory, 'positioner_sample_resolution' missing 'name' entry!");
71 if (YAML::Node n = joint[
"value"])
72 values[0] = n.as<
double>();
74 throw std::runtime_error(
"REPInvKinFactory, 'positioner_sample_resolution' missing 'value' entry!");
76 auto jnt = scene_graph.
getJoint(joint_name);
78 throw std::runtime_error(
"REPInvKinFactory, 'positioner_sample_resolution' failed to find joint in scene "
81 values[1] = jnt->limits->lower;
82 values[2] = jnt->limits->upper;
84 if (YAML::Node min = joint[
"min"])
85 values[1] = min.as<
double>();
87 if (YAML::Node max = joint[
"max"])
88 values[2] = max.as<
double>();
90 if (values[1] < jnt->limits->lower)
91 throw std::runtime_error(
"REPInvKinFactory, sample range minimum is less than joint minimum!");
93 if (values[2] > jnt->limits->upper)
94 throw std::runtime_error(
"REPInvKinFactory, sample range maximum is greater than joint maximum!");
96 if (values[1] > values[2])
97 throw std::runtime_error(
"REPInvKinFactory, sample range is not valid!");
99 sample_res_map[joint_name] = values;
104 throw std::runtime_error(
"REPInvKinFactory, missing 'positioner_sample_resolution' entry!");
108 if (YAML::Node positioner = config[
"positioner"])
111 if (YAML::Node n = positioner[
"class"])
114 throw std::runtime_error(
"REPInvKinFactory, 'positioner' missing 'class' entry!");
116 if (YAML::Node n = positioner[
"config"])
120 if (fwd_kin ==
nullptr)
121 throw std::runtime_error(
"REPInvKinFactory, failed to create positioner forward kinematics!");
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!");
128 throw std::runtime_error(
"REPInvKinFactory, missing 'positioner' entry!");
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)
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 +
"'!");
142 sample_res(i) = it->second[0];
143 sample_range(i, 0) = it->second[1];
144 sample_range(i, 1) = it->second[2];
148 if (YAML::Node manipulator = config[
"manipulator"])
151 if (YAML::Node n = manipulator[
"class"])
154 throw std::runtime_error(
"REPInvKinFactory, 'manipulator' missing 'class' entry!");
156 if (YAML::Node n = manipulator[
"config"])
160 if (inv_kin ==
nullptr)
161 throw std::runtime_error(
"REPInvKinFactory, failed to create positioner inverse kinematics!");
165 throw std::runtime_error(
"REPInvKinFactory, missing 'manipulator' entry!");
168 catch (
const std::exception& e)
170 CONSOLE_BRIDGE_logError(
"REPInvKinFactory: Failed to parse yaml config data! Details: %s", e.what());
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);
178 PLUGIN_ANCHOR_IMPL(REPInvKinFactoriesAnchor)