HEBI C++ API  3.12.2
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
kinematics_helper.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include "Eigen/Dense"
4 
5 #include "robot_model.hpp"
6 
7 namespace hebi {
8 namespace arm {
9 namespace internal {
10 
11 // A small helper class for computing IK and storing preferences about how this is done.
13 
14 public:
15  void setJointLimits(
16  const robot_model::RobotModel& robot_model,
17  const Eigen::VectorXd& min_positions,
18  const Eigen::VectorXd& max_positions);
19 
20  void clearJointLimits();
21 
22  Eigen::Vector3d FK3Dof(
23  const robot_model::RobotModel& robot_model,
24  const Eigen::VectorXd& positions) const;
25 
26  void FK5Dof(
27  const robot_model::RobotModel& robot_model,
28  const Eigen::VectorXd& positions,
29  Eigen::Vector3d& xyz_out,
30  Eigen::Vector3d& tip_axis) const;
31 
32  void FK6Dof(
33  const robot_model::RobotModel& robot_model,
34  const Eigen::VectorXd& positions,
35  Eigen::Vector3d& xyz_out,
36  Eigen::Matrix3d& orientation) const;
37 
38  Eigen::VectorXd solveIK3Dof(
39  const robot_model::RobotModel& robot_model,
40  const Eigen::VectorXd& initial_positions,
41  const Eigen::Vector3d& target_xyz) const;
42 
43  Eigen::VectorXd solveIK5Dof(
44  const robot_model::RobotModel& robot_model,
45  const Eigen::VectorXd& initial_positions,
46  const Eigen::Vector3d& target_xyz,
47  const Eigen::Vector3d& end_tip) const;
48 
49  Eigen::VectorXd solveIK6Dof(
50  const robot_model::RobotModel& robot_model,
51  const Eigen::VectorXd& initial_positions,
52  const Eigen::Vector3d& target_xyz,
53  const Eigen::Matrix3d& orientation) const;
54 
55 private:
56  bool use_joint_limits_{};
57  Eigen::VectorXd min_positions_{};
58  Eigen::VectorXd max_positions_{};
59 };
60 
61 } // namespace internal
62 } // namespace arm
63 } // namespace hebi
void setJointLimits(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: kinematics_helper.cpp:7
Eigen::VectorXd solveIK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Definition: kinematics_helper.cpp:44
Eigen::VectorXd solveIK6Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const
Definition: kinematics_helper.cpp:97
Definition: arm.cpp:10
Represents a chain or tree of robot elements (rigid bodies and joints).
Definition: robot_model.hpp:412
void FK5Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
Definition: kinematics_helper.cpp:134
Definition: arm.cpp:11
Eigen::VectorXd solveIK5Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
Definition: kinematics_helper.cpp:69
Definition: kinematics_helper.hpp:12
Eigen::Vector3d FK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions) const
Definition: kinematics_helper.cpp:125
void clearJointLimits()
Definition: kinematics_helper.cpp:37
void FK6Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
Definition: kinematics_helper.cpp:146