#include <KNIKinematics.h>
Public Member Functions | |
KNIKinematics () | |
virtual | ~KNIKinematics () |
Private Member Functions | |
bool | get_kinematic_solver_info (moveit_msgs::GetKinematicSolverInfo::Request &req, moveit_msgs::GetKinematicSolverInfo::Response &res) |
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 | |
Private Attributes | |
KNIConverter * | converter_ |
ros::ServiceServer | get_fk_server_ |
ros::ServiceServer | get_ik_server_ |
ros::ServiceServer | get_kinematic_solver_info_server_ |
CikBase | ikBase_ |
std::vector < moveit_msgs::JointLimits > | joint_limits_ |
std::vector< std::string > | joint_names_ |
ros::NodeHandle | nh_ |
tf::TransformListener | tf_listener_ |
Definition at line 49 of file KNIKinematics.h.
Definition at line 30 of file KNIKinematics.cpp.
katana::KNIKinematics::~KNIKinematics | ( | ) | [virtual] |
Definition at line 113 of file KNIKinematics.cpp.
bool katana::KNIKinematics::get_kinematic_solver_info | ( | moveit_msgs::GetKinematicSolverInfo::Request & | req, |
moveit_msgs::GetKinematicSolverInfo::Response & | res | ||
) | [private] |
Definition at line 118 of file KNIKinematics.cpp.
bool katana::KNIKinematics::get_position_fk | ( | moveit_msgs::GetPositionFK::Request & | req, |
moveit_msgs::GetPositionFK::Response & | res | ||
) | [private] |
Definition at line 127 of file KNIKinematics.cpp.
bool katana::KNIKinematics::get_position_ik | ( | moveit_msgs::GetPositionIK::Request & | req, |
moveit_msgs::GetPositionIK::Response & | res | ||
) | [private] |
Definition at line 190 of file KNIKinematics.cpp.
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.
jointAngles | the joint angles to compute the pose for (direct kinematics) |
Definition at line 299 of file KNIKinematics.cpp.
std::vector< int > katana::KNIKinematics::makeJointsLookup | ( | std::vector< std::string > & | joint_names | ) | [private] |
copied from joint_trajectory_action_controller
Definition at line 269 of file KNIKinematics.cpp.
KNIConverter* katana::KNIKinematics::converter_ [private] |
Definition at line 65 of file KNIKinematics.h.
Definition at line 58 of file KNIKinematics.h.
Definition at line 59 of file KNIKinematics.h.
Definition at line 57 of file KNIKinematics.h.
CikBase katana::KNIKinematics::ikBase_ [private] |
Definition at line 64 of file KNIKinematics.h.
std::vector<moveit_msgs::JointLimits> katana::KNIKinematics::joint_limits_ [private] |
Definition at line 62 of file KNIKinematics.h.
std::vector<std::string> katana::KNIKinematics::joint_names_ [private] |
Definition at line 61 of file KNIKinematics.h.
ros::NodeHandle katana::KNIKinematics::nh_ [private] |
Definition at line 56 of file KNIKinematics.h.
Definition at line 66 of file KNIKinematics.h.