26 #ifndef TESSERACT_KINEMATICS_IMPL_IKFAST_INV_KIN_HPP
27 #define TESSERACT_KINEMATICS_IMPL_IKFAST_INV_KIN_HPP
32 #include <console_bridge/console.h>
42 std::string tip_link_name,
43 std::vector<std::string> joint_names,
44 std::string solver_name,
45 std::vector<std::vector<double>> free_joint_states)
46 : base_link_name_(std::move(base_link_name))
47 , tip_link_name_(std::move(tip_link_name))
48 , joint_names_(std::move(joint_names))
49 , solver_name_(std::move(solver_name))
50 , free_joint_states_(std::move(free_joint_states))
70 const Eigen::Ref<const Eigen::VectorXd>& )
const
72 assert(tip_link_poses.size() == 1);
73 assert(tip_link_poses.find(
tip_link_name_) != tip_link_poses.end());
74 assert(std::abs(1.0 - tip_link_poses.at(
tip_link_name_).matrix().determinant()) < 1e-6);
79 Eigen::Transform<IkReal, 3, Eigen::Isometry> ikfast_tcp = pose.cast<IkReal>();
82 const Eigen::Matrix<IkReal, 3, 1> translation = ikfast_tcp.translation();
86 const Eigen::Matrix<IkReal, 3, 3, Eigen::RowMajor> rotation = ikfast_tcp.rotation();
88 auto ikfast_dof =
static_cast<std::size_t
>(
numJoints());
92 std::vector<double> sols;
95 auto addSols = [&](
const double* pfree) {
96 ComputeIk(translation.data(), rotation.data(), pfree, ikfast_solution_set);
101 std::vector<IkReal> ikfast_output;
102 ikfast_output.resize(n_sols * ikfast_dof);
104 for (std::size_t i = 0; i < n_sols; ++i)
107 const auto& sol = ikfast_solution_set.
GetSolution(i);
108 auto* out = ikfast_output.data() + i * ikfast_dof;
109 sol.GetSolution(out, pfree);
113 end(sols), std::make_move_iterator(ikfast_output.begin()), std::make_move_iterator(ikfast_output.end()));
120 addSols(j_combo.data());
129 std::size_t num_sol = sols.size() / ikfast_dof;
131 solution_set.reserve(sols.size());
132 for (std::size_t i = 0; i < num_sol; i++)
134 Eigen::Map<Eigen::VectorXd> eigen_sol(sols.data() + ikfast_dof * i,
static_cast<Eigen::Index
>(ikfast_dof));
135 if (eigen_sol.array().allFinite())
136 solution_set.push_back(eigen_sol);
149 inline std::vector<std::vector<double>>
152 std::vector<std::vector<double>> free_joint_states;
153 std::vector<std::size_t> curr_joint_indices(free_joint_samples.size(), 0);
154 while (curr_joint_indices.front() < free_joint_samples.front().size())
156 std::vector<double> curr_joint_values;
157 for (std::size_t i = 0; i < curr_joint_indices.size(); ++i)
158 curr_joint_values.push_back(free_joint_samples[i][curr_joint_indices[i]]);
159 free_joint_states.push_back(curr_joint_values);
160 curr_joint_indices.back()++;
161 for (std::size_t i = curr_joint_indices.size() - 1; i > 0; --i)
163 if (curr_joint_indices[i] == free_joint_samples[i].size())
165 curr_joint_indices[i] = 0;
166 curr_joint_indices[i - 1]++;
170 return free_joint_states;
175 #endif // TESSERACT_KINEMATICS_IMPL_IKFAST_INV_KIN_HPP