17 const Eigen::VectorXd& min_positions,
18 const Eigen::VectorXd& max_positions);
24 const Eigen::VectorXd& positions)
const;
28 const Eigen::VectorXd& positions,
29 Eigen::Vector3d& xyz_out,
30 Eigen::Vector3d& tip_axis)
const;
34 const Eigen::VectorXd& positions,
35 Eigen::Vector3d& xyz_out,
36 Eigen::Matrix3d& orientation)
const;
40 const Eigen::VectorXd& initial_positions,
41 const Eigen::Vector3d& target_xyz)
const;
45 const Eigen::VectorXd& initial_positions,
46 const Eigen::Vector3d& target_xyz,
47 const Eigen::Vector3d& end_tip)
const;
51 const Eigen::VectorXd& initial_positions,
52 const Eigen::Vector3d& target_xyz,
53 const Eigen::Matrix3d& orientation)
const;
56 bool use_joint_limits_{};
57 Eigen::VectorXd min_positions_{};
58 Eigen::VectorXd max_positions_{};
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
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
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