rep_inv_kin.cpp
Go to the documentation of this file.
1 
32 
33 namespace tesseract_kinematics
34 {
35 using Eigen::MatrixXd;
36 using Eigen::VectorXd;
37 
39  const tesseract_scene_graph::SceneState& scene_state,
40  InverseKinematics::UPtr manipulator,
41  double manipulator_reach,
42  std::unique_ptr<ForwardKinematics> positioner,
43  const Eigen::VectorXd& positioner_sample_resolution,
44  std::string solver_name)
45 {
46  if (positioner == nullptr)
47  throw std::runtime_error("Provided positioner is a nullptr");
48 
49  if (!scene_graph.getLink(scene_graph.getRoot()))
50  throw std::runtime_error("The scene graph has an invalid root.");
51 
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)
57  {
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;
61  }
62 
63  init(scene_graph,
64  scene_state,
65  std::move(manipulator),
66  manipulator_reach,
67  std::move(positioner),
68  positioner_limits,
69  positioner_sample_resolution,
70  std::move(solver_name));
71 }
72 
74  const tesseract_scene_graph::SceneState& scene_state,
75  InverseKinematics::UPtr manipulator,
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)
81 {
82  init(scene_graph,
83  scene_state,
84  std::move(manipulator),
85  manipulator_reach,
86  std::move(positioner),
87  positioner_sample_range,
88  positioner_sample_resolution,
89  std::move(solver_name));
90 }
91 
93  const tesseract_scene_graph::SceneState& scene_state,
94  InverseKinematics::UPtr manipulator,
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)
100 {
101  if (solver_name.empty())
102  throw std::runtime_error("Solver name must not be empty.");
103 
104  if (!scene_graph.getLink(scene_graph.getRoot()))
105  throw std::runtime_error("The scene graph has an invalid root.");
106 
107  if (manipulator == nullptr)
108  throw std::runtime_error("Provided manipulator is a nullptr");
109 
110  if (!(manipulator_reach > 0))
111  throw std::runtime_error("Manipulator reach is not greater than zero");
112 
113  if (positioner == nullptr)
114  throw std::runtime_error("Provided positioner is a nullptr");
115 
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");
118 
119  for (long i = 0; i < positioner_sample_resolution.size(); ++i)
120  {
121  if (!(positioner_sample_resolution(i) > 0))
122  throw std::runtime_error("Positioner sample resolution is not greater than zero");
123  }
124 
125  manip_base_to_positioner_base_ = scene_state.link_transforms.at(manipulator->getBaseLinkName()).inverse() *
126  scene_state.link_transforms.at(positioner->getBaseLinkName());
127 
128  solver_name_ = std::move(solver_name);
129  manip_inv_kin_ = manipulator->clone();
130  manip_reach_ = manipulator_reach;
131  positioner_fwd_kin_ = positioner->clone();
132  working_frame_ = positioner_fwd_kin_->getTipLinkNames()[0];
133  manip_tip_link_ = manip_inv_kin_->getTipLinkNames()[0];
134  dof_ = positioner_fwd_kin_->numJoints() + manip_inv_kin_->numJoints();
135 
136  joint_names_ = positioner_fwd_kin_->getJointNames();
137  const auto& manip_joints = manip_inv_kin_->getJointNames();
138  joint_names_.insert(joint_names_.end(), manip_joints.begin(), manip_joints.end());
139 
140  // For the kinematics object to be sampled we need to create the joint values at the sampling resolution
141  // The sampled joints results are stored in dof_range[joint index] to be used by the nested_ik function
142  auto positioner_num_joints = static_cast<int>(positioner_fwd_kin_->numJoints());
143  dof_range_.reserve(static_cast<std::size_t>(positioner_num_joints));
144  for (int d = 0; d < positioner_num_joints; ++d)
145  {
146  // given the sampling resolution for the joint calculate the number of samples such that the resolution is not
147  // exceeded.
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))) +
150  1;
151  dof_range_.emplace_back(
152  Eigen::VectorXd::LinSpaced(cnt, poitioner_sample_range(d, 0), poitioner_sample_range(d, 1)));
153  }
154 }
155 
156 InverseKinematics::UPtr REPInvKin::clone() const { return std::make_unique<REPInvKin>(*this); }
157 
158 REPInvKin::REPInvKin(const REPInvKin& other) { *this = other; }
159 
161 {
162  manip_inv_kin_ = other.manip_inv_kin_->clone();
163  positioner_fwd_kin_ = other.positioner_fwd_kin_->clone();
164  manip_reach_ = other.manip_reach_;
165  joint_names_ = other.joint_names_;
169  dof_ = other.dof_;
170  dof_range_ = other.dof_range_;
171 
172  return *this;
173 }
174 
176  const Eigen::Ref<const Eigen::VectorXd>& seed) const
177 {
178  Eigen::VectorXd positioner_pose(positioner_fwd_kin_->numJoints());
179  IKSolutions solutions;
180  nested_ik(solutions, 0, dof_range_, tip_link_poses, positioner_pose, seed);
181  return solutions;
182 }
183 
185  int loop_level,
186  const std::vector<Eigen::VectorXd>& dof_range,
187  const tesseract_common::TransformMap& tip_link_poses,
188  Eigen::VectorXd& positioner_pose,
189  const Eigen::Ref<const Eigen::VectorXd>& seed) const
190 {
191  if (loop_level >= static_cast<int>(positioner_fwd_kin_->numJoints()))
192  {
193  ikAt(solutions, tip_link_poses, positioner_pose, seed);
194  return;
195  }
196 
197  for (long i = 0; i < static_cast<long>(dof_range[static_cast<std::size_t>(loop_level)].size()); ++i)
198  {
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);
201  }
202 }
203 
204 void REPInvKin::ikAt(IKSolutions& solutions,
205  const tesseract_common::TransformMap& tip_link_poses,
206  Eigen::VectorXd& positioner_pose,
207  const Eigen::Ref<const Eigen::VectorXd>& seed) const
208 {
209  tesseract_common::TransformMap positioner_poses = positioner_fwd_kin_->calcFwdKin(positioner_pose);
210  Eigen::Isometry3d positioner_tf = positioner_poses[working_frame_];
211 
212  Eigen::Isometry3d robot_target_pose =
213  manip_base_to_positioner_base_ * positioner_tf * tip_link_poses.at(manip_tip_link_);
214  if (robot_target_pose.translation().norm() > manip_reach_)
215  return;
216 
217  tesseract_common::TransformMap robot_target_poses{ std::make_pair(manip_tip_link_, robot_target_pose) };
218  auto robot_dof = static_cast<Eigen::Index>(manip_inv_kin_->numJoints());
219  auto positioner_dof = static_cast<Eigen::Index>(positioner_pose.size());
220 
221  IKSolutions robot_solution_set = manip_inv_kin_->calcInvKin(robot_target_poses, seed.tail(robot_dof));
222  if (robot_solution_set.empty())
223  return;
224 
225  for (const auto& robot_solution : robot_solution_set)
226  {
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);
232  }
233 }
234 
236  const Eigen::Ref<const Eigen::VectorXd>& seed) const
237 {
238  // NOLINTNEXTLINE(clang-analyzer-core.UndefinedBinaryOperatorResult)
239  assert(tip_link_poses.find(manip_tip_link_) != tip_link_poses.end());
240  assert(std::abs(1.0 - tip_link_poses.at(manip_tip_link_).matrix().determinant()) < 1e-6); // NOLINT
241 
242  return calcInvKinHelper(tip_link_poses, seed);
243 }
244 
245 std::vector<std::string> REPInvKin::getJointNames() const { return joint_names_; }
246 
247 Eigen::Index REPInvKin::numJoints() const { return dof_; }
248 
249 std::string REPInvKin::getBaseLinkName() const { return manip_inv_kin_->getBaseLinkName(); }
250 
251 std::string REPInvKin::getWorkingFrame() const { return working_frame_; }
252 
253 std::vector<std::string> REPInvKin::getTipLinkNames() const { return { manip_tip_link_ }; }
254 
255 std::string REPInvKin::getSolverName() const { return solver_name_; }
256 
257 } // namespace tesseract_kinematics
graph.h
tesseract_kinematics::REPInvKin::getWorkingFrame
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Definition: rep_inv_kin.cpp:251
tesseract_kinematics::REPInvKin::manip_tip_link_
std::string manip_tip_link_
Definition: rep_inv_kin.h:121
tesseract_kinematics::REPInvKin::solver_name_
std::string solver_name_
Name of this solver.
Definition: rep_inv_kin.h:126
tesseract_kinematics::REPInvKin::REPInvKin
REPInvKin(const REPInvKin &other)
Definition: rep_inv_kin.cpp:158
tesseract_kinematics::REPInvKin::nested_ik
void nested_ik(IKSolutions &solutions, int loop_level, const std::vector< Eigen::VectorXd > &dof_range, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
Definition: rep_inv_kin.cpp:184
tesseract_kinematics::REPInvKin::calcInvKin
IKSolutions calcInvKin(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override final
Calculates joint solutions given a pose for each tip link.
Definition: rep_inv_kin.cpp:235
tesseract_kinematics::REPInvKin::manip_inv_kin_
InverseKinematics::UPtr manip_inv_kin_
Definition: rep_inv_kin.h:118
rep_inv_kin.h
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
joint.h
tesseract_kinematics::REPInvKin::getJointNames
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: rep_inv_kin.cpp:245
tesseract_kinematics::REPInvKin::manip_reach_
double manip_reach_
Definition: rep_inv_kin.h:122
tesseract_scene_graph::SceneGraph
tesseract_kinematics::REPInvKin::clone
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: rep_inv_kin.cpp:156
tesseract_kinematics::REPInvKin::getBaseLinkName
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: rep_inv_kin.cpp:249
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
tesseract_scene_graph::SceneState
tesseract_kinematics::REPInvKin::dof_range_
std::vector< Eigen::VectorXd > dof_range_
Definition: rep_inv_kin.h:125
tesseract_kinematics::REPInvKin::working_frame_
std::string working_frame_
Definition: rep_inv_kin.h:120
tesseract_kinematics::REPInvKin::positioner_fwd_kin_
std::unique_ptr< ForwardKinematics > positioner_fwd_kin_
Definition: rep_inv_kin.h:119
forward_kinematics.h
Forward kinematics functions.
tesseract_kinematics::REPInvKin::dof_
Eigen::Index dof_
Definition: rep_inv_kin.h:124
tesseract_kinematics::REPInvKin::numJoints
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: rep_inv_kin.cpp:247
tesseract_kinematics::REPInvKin::ikAt
void ikAt(IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const
Definition: rep_inv_kin.cpp:204
scene_state.h
tesseract_kinematics::REPInvKin::init
void init(const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::MatrixX2d &poitioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_REP_INV_KIN_SOLVER_NAME)
Definition: rep_inv_kin.cpp:92
tesseract_scene_graph::SceneGraph::getRoot
const std::string & getRoot() const
tesseract_scene_graph::SceneGraph::getJoint
std::shared_ptr< const Joint > getJoint(const std::string &name) const
tesseract_kinematics::REPInvKin::operator=
REPInvKin & operator=(const REPInvKin &other)
Definition: rep_inv_kin.cpp:160
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::REPInvKin
Robot With External Positioner Inverse kinematic implementation.
Definition: rep_inv_kin.h:49
tesseract_scene_graph::SceneGraph::getLink
std::shared_ptr< const Link > getLink(const std::string &name) const
tesseract_kinematics::REPInvKin::getSolverName
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: rep_inv_kin.cpp:255
tesseract_scene_graph::SceneState::link_transforms
tesseract_common::TransformMap link_transforms
tesseract_kinematics::REPInvKin::joint_names_
std::vector< std::string > joint_names_
Definition: rep_inv_kin.h:117
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
tesseract_kinematics::REPInvKin::manip_base_to_positioner_base_
Eigen::Isometry3d manip_base_to_positioner_base_
Definition: rep_inv_kin.h:123
tesseract_kinematics::REPInvKin::getTipLinkNames
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
Definition: rep_inv_kin.cpp:253
tesseract_kinematics::REPInvKin::calcInvKinHelper
IKSolutions calcInvKinHelper(const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const
calcFwdKin helper function
Definition: rep_inv_kin.cpp:175


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