Provides services for JACO kinematics. More...
#include <jaco_kinematics.h>
Public Member Functions | |
geometry_msgs::PoseStamped | calculateFK (std::vector< float > joints) |
Calculates the forward kinematics for the JACO arm. | |
bool | callFK (wpi_jaco_msgs::JacoFK::Request &req, wpi_jaco_msgs::JacoFK::Response &res) |
Callback for the forward kinematics service. | |
tf::Transform | generateTransform (float theta, float d, float a, float alpha) |
Generates a transform given D-H parameters. | |
JacoKinematics (void) | |
Private Member Functions | |
bool | loadParameters (const ros::NodeHandle n) |
Private Attributes | |
std::vector< double > | alphas |
alpha parameters in the D-H convention | |
std::string | arm_name_ |
std::vector< double > | as |
a parameters in the D-H convention | |
std::vector< double > | ds |
d parameters in the D-H convention | |
ros::ServiceServer | fkServer |
ros::NodeHandle | n |
std::string | topic_prefix_ |
Provides services for JACO kinematics.
JacoKinematics creates a ROS node that provides services for converting calculating kinematics for the JACO arm.
Definition at line 45 of file jaco_kinematics.h.
JacoKinematics::JacoKinematics | ( | void | ) |
Definition at line 5 of file jaco_kinematics.cpp.
geometry_msgs::PoseStamped JacoKinematics::calculateFK | ( | std::vector< float > | joints | ) |
Calculates the forward kinematics for the JACO arm.
joints | vector of joint angles from the arm |
Definition at line 90 of file jaco_kinematics.cpp.
bool JacoKinematics::callFK | ( | wpi_jaco_msgs::JacoFK::Request & | req, |
wpi_jaco_msgs::JacoFK::Response & | res | ||
) |
Callback for the forward kinematics service.
req | service request |
res | service response |
Definition at line 77 of file jaco_kinematics.cpp.
tf::Transform JacoKinematics::generateTransform | ( | float | theta, |
float | d, | ||
float | a, | ||
float | alpha | ||
) |
Generates a transform given D-H parameters.
theta | joint angle |
d | link length |
a | offset |
alpha | angle offset |
Definition at line 136 of file jaco_kinematics.cpp.
bool JacoKinematics::loadParameters | ( | const ros::NodeHandle | n | ) | [private] |
Definition at line 160 of file jaco_kinematics.cpp.
std::vector<double> JacoKinematics::alphas [private] |
alpha parameters in the D-H convention
Definition at line 89 of file jaco_kinematics.h.
std::string JacoKinematics::arm_name_ [private] |
Definition at line 83 of file jaco_kinematics.h.
std::vector<double> JacoKinematics::as [private] |
a parameters in the D-H convention
Definition at line 88 of file jaco_kinematics.h.
std::vector<double> JacoKinematics::ds [private] |
d parameters in the D-H convention
Definition at line 87 of file jaco_kinematics.h.
ros::ServiceServer JacoKinematics::fkServer [private] |
Definition at line 81 of file jaco_kinematics.h.
ros::NodeHandle JacoKinematics::n [private] |
Definition at line 80 of file jaco_kinematics.h.
std::string JacoKinematics::topic_prefix_ [private] |
Definition at line 84 of file jaco_kinematics.h.