Public Member Functions | Private Member Functions | Private Attributes
JacoConversions Class Reference

Provides services for conversions between 3D rotation representations. More...

#include <jaco_conversions.h>

List of all members.

Public Member Functions

bool callEQ (wpi_jaco_msgs::EulerToQuaternion::Request &req, wpi_jaco_msgs::EulerToQuaternion::Response &res)
 Callback for the Euler to Quaternion service.
bool callQE (wpi_jaco_msgs::QuaternionToEuler::Request &req, wpi_jaco_msgs::QuaternionToEuler::Response &res)
 Callback for the Quaternion to Euler service.
 JacoConversions (void)

Private Member Functions

bool loadParameters (const ros::NodeHandle n)

Private Attributes

std::string arm_name_
ros::ServiceServer eqServer
ros::NodeHandle n
ros::ServiceServer qeServer
std::string topic_prefix_

Detailed Description

Provides services for conversions between 3D rotation representations.

.h jaco_conversions creates a ROS node that provides services for converting between the JACO's internal representation of 3D rotations (Euler xyz convention) and commonly used representations in ROS (quaternions)

Author:
David Kent, GT - dekent@gatech.edu

Provides services for conversions between 3D rotation representations.

JacoConversions creates a ROS node that provides services for converting between the JACO's internal representation of 3D rotations (Euler xyz convention) and commonly used representations in ROS (quaternions)

Definition at line 27 of file jaco_conversions.h.


Constructor & Destructor Documentation

Definition at line 5 of file jaco_conversions.cpp.


Member Function Documentation

bool JacoConversions::callEQ ( wpi_jaco_msgs::EulerToQuaternion::Request &  req,
wpi_jaco_msgs::EulerToQuaternion::Response &  res 
)

Callback for the Euler to Quaternion service.

Parameters:
reqservice request
resservice response
Returns:
true on success

Definition at line 14 of file jaco_conversions.cpp.

bool JacoConversions::callQE ( wpi_jaco_msgs::QuaternionToEuler::Request &  req,
wpi_jaco_msgs::QuaternionToEuler::Response &  res 
)

Callback for the Quaternion to Euler service.

Parameters:
reqservice request
resservice response
Returns:
true on success

Definition at line 30 of file jaco_conversions.cpp.

bool JacoConversions::loadParameters ( const ros::NodeHandle  n) [private]
Todo:
MdL [IMPR]: Return is values are all correctly loaded.

Definition at line 53 of file jaco_conversions.cpp.


Member Data Documentation

std::string JacoConversions::arm_name_ [private]

Definition at line 57 of file jaco_conversions.h.

Definition at line 54 of file jaco_conversions.h.

Definition at line 53 of file jaco_conversions.h.

Definition at line 55 of file jaco_conversions.h.

std::string JacoConversions::topic_prefix_ [private]

Definition at line 58 of file jaco_conversions.h.


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


wpi_jaco_wrapper
Author(s): David Kent
autogenerated on Thu Jun 6 2019 19:43:31