#include <pr2_arm_kinematics.h>
|
bool | getFKSolverInfo (kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response) |
| This is the basic kinematics info service that will return information about the kinematics node. More...
|
|
bool | getIKSolverInfo (kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response) |
| This is the basic kinematics info service that will return information about the kinematics node. More...
|
|
bool | getPositionFK (kinematics_msgs::GetPositionFK::Request &request, kinematics_msgs::GetPositionFK::Response &response) |
| This is the basic forward kinematics service that will return information about the kinematics node. More...
|
|
virtual bool | getPositionIK (kinematics_msgs::GetPositionIK::Request &request, kinematics_msgs::GetPositionIK::Response &response) |
| This is the basic IK service method that will compute and return an IK solution. More...
|
|
bool | isActive () |
| Specifies if the node is active or not. More...
|
|
| PR2ArmKinematics (bool create_transform_listener=true) |
|
virtual | ~PR2ArmKinematics () |
|
|
bool | getPositionIKHelper (kinematics_msgs::GetPositionIK::Request &request, kinematics_msgs::GetPositionIK::Response &response) |
|
virtual bool | transformPose (const std::string &des_frame, const geometry_msgs::PoseStamped &pose_in, geometry_msgs::PoseStamped &pose_out) |
|
Definition at line 59 of file pr2_arm_kinematics.h.
pr2_arm_kinematics::PR2ArmKinematics::PR2ArmKinematics |
( |
bool |
create_transform_listener = true | ) |
|
pr2_arm_kinematics::PR2ArmKinematics::~PR2ArmKinematics |
( |
| ) |
|
|
virtual |
bool pr2_arm_kinematics::PR2ArmKinematics::getFKSolverInfo |
( |
kinematics_msgs::GetKinematicSolverInfo::Request & |
request, |
|
|
kinematics_msgs::GetKinematicSolverInfo::Response & |
response |
|
) |
| |
This is the basic kinematics info service that will return information about the kinematics node.
- Parameters
-
A | request message. See service definition for GetKinematicSolverInfo for more information on this message. |
The | response message. See service definition for GetKinematicSolverInfo for more information on this message. |
Definition at line 241 of file pr2_arm_kinematics.cpp.
bool pr2_arm_kinematics::PR2ArmKinematics::getIKSolverInfo |
( |
kinematics_msgs::GetKinematicSolverInfo::Request & |
request, |
|
|
kinematics_msgs::GetKinematicSolverInfo::Response & |
response |
|
) |
| |
This is the basic kinematics info service that will return information about the kinematics node.
- Parameters
-
A | request message. See service definition for GetKinematicSolverInfo for more information on this message. |
The | response message. See service definition for GetKinematicSolverInfo for more information on this message. |
Definition at line 229 of file pr2_arm_kinematics.cpp.
bool pr2_arm_kinematics::PR2ArmKinematics::getPositionFK |
( |
kinematics_msgs::GetPositionFK::Request & |
request, |
|
|
kinematics_msgs::GetPositionFK::Response & |
response |
|
) |
| |
This is the basic forward kinematics service that will return information about the kinematics node.
- Parameters
-
A | request message. See service definition for GetPositionFK for more information on this message. |
The | response message. See service definition for GetPositionFK for more information on this message. |
Definition at line 253 of file pr2_arm_kinematics.cpp.
bool pr2_arm_kinematics::PR2ArmKinematics::getPositionIK |
( |
kinematics_msgs::GetPositionIK::Request & |
request, |
|
|
kinematics_msgs::GetPositionIK::Response & |
response |
|
) |
| |
|
virtual |
This is the basic IK service method that will compute and return an IK solution.
- Parameters
-
A | request message. See service definition for GetPositionIK for more information on this message. |
The | response message. See service definition for GetPositionIK for more information on this message. |
Definition at line 145 of file pr2_arm_kinematics.cpp.
bool pr2_arm_kinematics::PR2ArmKinematics::getPositionIKHelper |
( |
kinematics_msgs::GetPositionIK::Request & |
request, |
|
|
kinematics_msgs::GetPositionIK::Response & |
response |
|
) |
| |
|
protected |
bool pr2_arm_kinematics::PR2ArmKinematics::isActive |
( |
| ) |
|
Specifies if the node is active or not.
- Returns
- True if the node is active, false otherwise.
Definition at line 138 of file pr2_arm_kinematics.cpp.
bool pr2_arm_kinematics::PR2ArmKinematics::transformPose |
( |
const std::string & |
des_frame, |
|
|
const geometry_msgs::PoseStamped & |
pose_in, |
|
|
geometry_msgs::PoseStamped & |
pose_out |
|
) |
| |
|
protectedvirtual |
bool pr2_arm_kinematics::PR2ArmKinematics::active_ |
|
protected |
int pr2_arm_kinematics::PR2ArmKinematics::dimension_ |
|
protected |
kinematics_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::fk_solver_info_ |
|
protected |
int pr2_arm_kinematics::PR2ArmKinematics::free_angle_ |
|
protected |
kinematics_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::ik_solver_info_ |
|
protected |
KDL::Chain pr2_arm_kinematics::PR2ArmKinematics::kdl_chain_ |
|
protected |
urdf::Model pr2_arm_kinematics::PR2ArmKinematics::robot_model_ |
|
protected |
std::string pr2_arm_kinematics::PR2ArmKinematics::root_name_ |
|
protected |
double pr2_arm_kinematics::PR2ArmKinematics::search_discretization_ |
|
protected |
The documentation for this class was generated from the following files: