moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <pr2_arm_ik.h>
Public Member Functions | |
PR2ArmIK () | |
~PR2ArmIK () | |
bool | init (const urdf::ModelInterface &robot_model, const std::string &root_name, const std::string &tip_name) |
Initialize the solver by providing a urdf::Model and a root and tip name. | |
void | computeIKShoulderPan (const Eigen::Isometry3f &g_in, double shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const |
compute IK based on an initial guess for the shoulder pan angle. | |
void | computeIKShoulderRoll (const Eigen::Isometry3f &g_in, double shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const |
compute IK based on an initial guess for the shoulder roll angle. h | |
void | getSolverInfo (moveit_msgs::msg::KinematicSolverInfo &info) |
get chain information about the arm. This populates the IK query response, filling in joint level information including names and joint limits. | |
Public Attributes | |
moveit_msgs::msg::KinematicSolverInfo | solver_info_ |
get chain information about the arm. | |
Definition at line 122 of file pr2_arm_ik.h.
pr2_arm_kinematics::PR2ArmIK::PR2ArmIK | ( | ) |
Definition at line 61 of file pr2_arm_ik.cpp.
|
inline |
Definition at line 131 of file pr2_arm_ik.h.
void pr2_arm_kinematics::PR2ArmIK::computeIKShoulderPan | ( | const Eigen::Isometry3f & | g_in, |
double | shoulder_pan_initial_guess, | ||
std::vector< std::vector< double > > & | solution | ||
) | const |
compute IK based on an initial guess for the shoulder pan angle.
Input | pose for end-effector |
Initial | guess for shoulder pan angle |
Definition at line 210 of file pr2_arm_ik.cpp.
void pr2_arm_kinematics::PR2ArmIK::computeIKShoulderRoll | ( | const Eigen::Isometry3f & | g_in, |
double | shoulder_roll_initial_guess, | ||
std::vector< std::vector< double > > & | solution | ||
) | const |
compute IK based on an initial guess for the shoulder roll angle. h
Input | pose for end-effector |
Initial | guess for shoulder roll angle |
Definition at line 475 of file pr2_arm_ik.cpp.
void pr2_arm_kinematics::PR2ArmIK::getSolverInfo | ( | moveit_msgs::msg::KinematicSolverInfo & | info | ) |
get chain information about the arm. This populates the IK query response, filling in joint level information including names and joint limits.
The | response structure to be filled in. |
Definition at line 205 of file pr2_arm_ik.cpp.
bool pr2_arm_kinematics::PR2ArmIK::init | ( | const urdf::ModelInterface & | robot_model, |
const std::string & | root_name, | ||
const std::string & | tip_name | ||
) |
Initialize the solver by providing a urdf::Model and a root and tip name.
A | urdf::Model representation of the PR2 robot model |
The | root joint name of the arm |
The | tip joint name of the arm |
Definition at line 65 of file pr2_arm_ik.cpp.
moveit_msgs::msg::KinematicSolverInfo pr2_arm_kinematics::PR2ArmIK::solver_info_ |
get chain information about the arm.
Definition at line 170 of file pr2_arm_ik.h.