moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | List of all members
pr2_arm_kinematics::PR2ArmIK Class Reference

#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. More...
 
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. More...
 
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 More...
 
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. More...
 

Public Attributes

moveit_msgs::msg::KinematicSolverInfo solver_info_
 get chain information about the arm. More...
 

Detailed Description

Definition at line 118 of file pr2_arm_ik.h.

Constructor & Destructor Documentation

◆ PR2ArmIK()

pr2_arm_kinematics::PR2ArmIK::PR2ArmIK ( )

Definition at line 61 of file pr2_arm_ik.cpp.

◆ ~PR2ArmIK()

pr2_arm_kinematics::PR2ArmIK::~PR2ArmIK ( )
inline

Definition at line 127 of file pr2_arm_ik.h.

Member Function Documentation

◆ computeIKShoulderPan()

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.

Parameters
Inputpose for end-effector
Initialguess for shoulder pan angle

Definition at line 210 of file pr2_arm_ik.cpp.

Here is the caller graph for this function:

◆ computeIKShoulderRoll()

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

Parameters
Inputpose for end-effector
Initialguess for shoulder roll angle

Definition at line 475 of file pr2_arm_ik.cpp.

Here is the caller graph for this function:

◆ getSolverInfo()

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.

Parameters
Theresponse structure to be filled in.

Definition at line 205 of file pr2_arm_ik.cpp.

Here is the caller graph for this function:

◆ init()

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.

Parameters
Aurdf::Model representation of the PR2 robot model
Theroot joint name of the arm
Thetip joint name of the arm
Returns
true if initialization was successful, false otherwise.

Definition at line 65 of file pr2_arm_ik.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ solver_info_

moveit_msgs::msg::KinematicSolverInfo pr2_arm_kinematics::PR2ArmIK::solver_info_

get chain information about the arm.

Definition at line 166 of file pr2_arm_ik.h.


The documentation for this class was generated from the following files: