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

#include <pr2_arm_kinematics_plugin.h>

Inheritance diagram for pr2_arm_kinematics::PR2ArmIKSolver:
Inheritance graph
[legend]
Collaboration diagram for pr2_arm_kinematics::PR2ArmIKSolver:
Collaboration graph
[legend]

Public Member Functions

 PR2ArmIKSolver (const urdf::ModelInterface &robot_model, const std::string &root_frame_name, const std::string &tip_frame_name, const double &search_discretization_angle, const int &free_angle)
 
 ~PR2ArmIKSolver () override
 
void updateInternalDataStructures () override
 
int CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
 
int cartToJntSearch (const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout)
 
void getSolverInfo (moveit_msgs::msg::KinematicSolverInfo &response)
 

Public Attributes

PR2ArmIK pr2_arm_ik_
 The PR2 inverse kinematics solver. More...
 
bool active_
 Indicates whether the solver has been successfully initialized. More...
 

Detailed Description

Definition at line 69 of file pr2_arm_kinematics_plugin.h.

Constructor & Destructor Documentation

◆ PR2ArmIKSolver()

pr2_arm_kinematics::PR2ArmIKSolver::PR2ArmIKSolver ( const urdf::ModelInterface &  robot_model,
const std::string &  root_frame_name,
const std::string &  tip_frame_name,
const double &  search_discretization_angle,
const int &  free_angle 
)

Definition at line 89 of file pr2_arm_kinematics_plugin.cpp.

Here is the call graph for this function:

◆ ~PR2ArmIKSolver()

pr2_arm_kinematics::PR2ArmIKSolver::~PR2ArmIKSolver ( )
inlineoverride

Definition at line 85 of file pr2_arm_kinematics_plugin.h.

Member Function Documentation

◆ CartToJnt()

int pr2_arm_kinematics::PR2ArmIKSolver::CartToJnt ( const KDL::JntArray &  q_init,
const KDL::Frame &  p_in,
KDL::JntArray &  q_out 
)
override

Definition at line 106 of file pr2_arm_kinematics_plugin.cpp.

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

◆ cartToJntSearch()

int pr2_arm_kinematics::PR2ArmIKSolver::cartToJntSearch ( const KDL::JntArray &  q_in,
const KDL::Frame &  p_in,
KDL::JntArray &  q_out,
const double &  timeout 
)

Definition at line 162 of file pr2_arm_kinematics_plugin.cpp.

Here is the call graph for this function:

◆ getSolverInfo()

void pr2_arm_kinematics::PR2ArmIKSolver::getSolverInfo ( moveit_msgs::msg::KinematicSolverInfo &  response)
inline

Definition at line 103 of file pr2_arm_kinematics_plugin.h.

Here is the call graph for this function:

◆ updateInternalDataStructures()

void pr2_arm_kinematics::PR2ArmIKSolver::updateInternalDataStructures ( )
override

Definition at line 100 of file pr2_arm_kinematics_plugin.cpp.

Member Data Documentation

◆ active_

bool pr2_arm_kinematics::PR2ArmIKSolver::active_

Indicates whether the solver has been successfully initialized.

Definition at line 97 of file pr2_arm_kinematics_plugin.h.

◆ pr2_arm_ik_

PR2ArmIK pr2_arm_kinematics::PR2ArmIKSolver::pr2_arm_ik_

The PR2 inverse kinematics solver.

Definition at line 92 of file pr2_arm_kinematics_plugin.h.


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