Public Member Functions | Private Member Functions | Private Attributes
katana::KNIKinematics Class Reference

#include <KNIKinematics.h>

List of all members.

Public Member Functions

 KNIKinematics ()
virtual ~KNIKinematics ()

Private Member Functions

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

KNIConverterconverter_
ros::ServiceServer get_fk_server_
ros::ServiceServer get_ik_server_
CikBase ikBase_
std::vector
< moveit_msgs::JointLimits > 
joint_limits_
std::vector< std::string > joint_names_
ros::NodeHandle nh_
tf::TransformListener tf_listener_

Detailed Description

Definition at line 49 of file KNIKinematics.h.


Constructor & Destructor Documentation

Definition at line 30 of file KNIKinematics.cpp.

Definition at line 110 of file KNIKinematics.cpp.


Member Function Documentation

bool katana::KNIKinematics::get_position_fk ( moveit_msgs::GetPositionFK::Request &  req,
moveit_msgs::GetPositionFK::Response &  res 
) [private]

Definition at line 115 of file KNIKinematics.cpp.

bool katana::KNIKinematics::get_position_ik ( moveit_msgs::GetPositionIK::Request &  req,
moveit_msgs::GetPositionIK::Response &  res 
) [private]

Definition at line 178 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.

Parameters:
jointAnglesthe 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]

copied from joint_trajectory_action_controller

Definition at line 257 of file KNIKinematics.cpp.


Member Data Documentation

Definition at line 64 of file KNIKinematics.h.

Definition at line 57 of file KNIKinematics.h.

Definition at line 58 of file KNIKinematics.h.

Definition at line 63 of file KNIKinematics.h.

std::vector<moveit_msgs::JointLimits> katana::KNIKinematics::joint_limits_ [private]

Definition at line 61 of file KNIKinematics.h.

std::vector<std::string> katana::KNIKinematics::joint_names_ [private]

Definition at line 60 of file KNIKinematics.h.

Definition at line 56 of file KNIKinematics.h.

Definition at line 65 of file KNIKinematics.h.


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


katana
Author(s): Martin Günther
autogenerated on Thu Jun 6 2019 21:43:33