#include <KNIKinematics.h>
|
bool | get_position_fk (moveit_msgs::GetPositionFK::Request &req, moveit_msgs::GetPositionFK::Response &res) |
|
bool | get_position_ik (moveit_msgs::GetPositionIK::Request &req, moveit_msgs::GetPositionIK::Response &res) |
|
std::vector< double > | getCoordinates () |
|
std::vector< double > | getCoordinates (std::vector< double > jointAngles) |
|
std::vector< int > | makeJointsLookup (std::vector< std::string > &joint_names) |
| copied from joint_trajectory_action_controller More...
|
|
Definition at line 49 of file KNIKinematics.h.
katana::KNIKinematics::KNIKinematics |
( |
| ) |
|
katana::KNIKinematics::~KNIKinematics |
( |
| ) |
|
|
virtual |
bool katana::KNIKinematics::get_position_fk |
( |
moveit_msgs::GetPositionFK::Request & |
req, |
|
|
moveit_msgs::GetPositionFK::Response & |
res |
|
) |
| |
|
private |
bool katana::KNIKinematics::get_position_ik |
( |
moveit_msgs::GetPositionIK::Request & |
req, |
|
|
moveit_msgs::GetPositionIK::Response & |
res |
|
) |
| |
|
private |
std::vector<double> katana::KNIKinematics::getCoordinates |
( |
| ) |
|
|
private |
std::vector< double > katana::KNIKinematics::getCoordinates |
( |
std::vector< double > |
jointAngles | ) |
|
|
private |
Return the position of the tool center point as calculated by the KNI.
- Parameters
-
jointAngles | the joint angles to compute the pose for (direct kinematics) |
- Returns
- a vector <x, y, z, r, p, y>; xyz in [m], rpy in [rad]
Definition at line 287 of file KNIKinematics.cpp.
std::vector< int > katana::KNIKinematics::makeJointsLookup |
( |
std::vector< std::string > & |
joint_names | ) |
|
|
private |
CikBase katana::KNIKinematics::ikBase_ |
|
private |
std::vector<moveit_msgs::JointLimits> katana::KNIKinematics::joint_limits_ |
|
private |
std::vector<std::string> katana::KNIKinematics::joint_names_ |
|
private |
The documentation for this class was generated from the following files: