35 using Eigen::MatrixXd;
36 using Eigen::VectorXd;
41 double manipulator_reach,
42 std::unique_ptr<ForwardKinematics> positioner,
43 const Eigen::VectorXd& positioner_sample_resolution,
44 std::string solver_name)
46 if (positioner ==
nullptr)
47 throw std::runtime_error(
"Provided positioner is a nullptr");
50 throw std::runtime_error(
"The scene graph has an invalid root.");
52 std::vector<std::string> joint_names = positioner->getJointNames();
53 auto s =
static_cast<Eigen::Index
>(joint_names.size());
54 Eigen::MatrixX2d positioner_limits;
55 positioner_limits.resize(s, 2);
56 for (Eigen::Index i = 0; i < s; ++i)
58 auto joint = scene_graph.
getJoint(joint_names[
static_cast<std::size_t
>(i)]);
59 positioner_limits(i, 0) = joint->limits->lower;
60 positioner_limits(i, 1) = joint->limits->upper;
65 std::move(manipulator),
67 std::move(positioner),
69 positioner_sample_resolution,
70 std::move(solver_name));
76 double manipulator_reach,
77 std::unique_ptr<ForwardKinematics> positioner,
78 const Eigen::MatrixX2d& positioner_sample_range,
79 const Eigen::VectorXd& positioner_sample_resolution,
80 std::string solver_name)
84 std::move(manipulator),
86 std::move(positioner),
87 positioner_sample_range,
88 positioner_sample_resolution,
89 std::move(solver_name));
95 double manipulator_reach,
96 std::unique_ptr<ForwardKinematics> positioner,
97 const Eigen::MatrixX2d& poitioner_sample_range,
98 const Eigen::VectorXd& positioner_sample_resolution,
99 std::string solver_name)
101 if (solver_name.empty())
102 throw std::runtime_error(
"Solver name must not be empty.");
105 throw std::runtime_error(
"The scene graph has an invalid root.");
107 if (manipulator ==
nullptr)
108 throw std::runtime_error(
"Provided manipulator is a nullptr");
110 if (!(manipulator_reach > 0))
111 throw std::runtime_error(
"Manipulator reach is not greater than zero");
113 if (positioner ==
nullptr)
114 throw std::runtime_error(
"Provided positioner is a nullptr");
116 if (positioner_sample_resolution.size() != positioner->numJoints())
117 throw std::runtime_error(
"Positioner sample resolution must be same size as positioner number of joints");
119 for (
long i = 0; i < positioner_sample_resolution.size(); ++i)
121 if (!(positioner_sample_resolution(i) > 0))
122 throw std::runtime_error(
"Positioner sample resolution is not greater than zero");
143 dof_range_.reserve(
static_cast<std::size_t
>(positioner_num_joints));
144 for (
int d = 0; d < positioner_num_joints; ++d)
148 int cnt =
static_cast<int>(std::ceil(std::abs(poitioner_sample_range(d, 1) - poitioner_sample_range(d, 0)) /
149 positioner_sample_resolution(d))) +
152 Eigen::VectorXd::LinSpaced(cnt, poitioner_sample_range(d, 0), poitioner_sample_range(d, 1)));
176 const Eigen::Ref<const Eigen::VectorXd>& seed)
const
186 const std::vector<Eigen::VectorXd>& dof_range,
188 Eigen::VectorXd& positioner_pose,
189 const Eigen::Ref<const Eigen::VectorXd>& seed)
const
193 ikAt(solutions, tip_link_poses, positioner_pose, seed);
197 for (
long i = 0; i < static_cast<long>(dof_range[
static_cast<std::size_t
>(loop_level)].size()); ++i)
199 positioner_pose(loop_level) = dof_range[
static_cast<std::size_t
>(loop_level)][i];
200 nested_ik(solutions, loop_level + 1, dof_range, tip_link_poses, positioner_pose, seed);
206 Eigen::VectorXd& positioner_pose,
207 const Eigen::Ref<const Eigen::VectorXd>& seed)
const
210 Eigen::Isometry3d positioner_tf = positioner_poses[
working_frame_];
212 Eigen::Isometry3d robot_target_pose =
214 if (robot_target_pose.translation().norm() >
manip_reach_)
218 auto robot_dof =
static_cast<Eigen::Index
>(
manip_inv_kin_->numJoints());
219 auto positioner_dof =
static_cast<Eigen::Index
>(positioner_pose.size());
222 if (robot_solution_set.empty())
225 for (
const auto& robot_solution : robot_solution_set)
227 Eigen::VectorXd full_sol;
228 full_sol.resize(positioner_dof + robot_dof);
229 full_sol.head(positioner_dof) = positioner_pose;
230 full_sol.tail(robot_dof) = robot_solution;
231 solutions.push_back(full_sol);
236 const Eigen::Ref<const Eigen::VectorXd>& seed)
const
240 assert(std::abs(1.0 - tip_link_poses.at(
manip_tip_link_).matrix().determinant()) < 1e-6);