Public Member Functions | Private Attributes
jaco::JacoComm Class Reference

#include <jaco_comm.h>

List of all members.

Public Member Functions

void getCartesianPosition (JacoPose &position)
 API call to obtain the current cartesian position of the arm.
void getConfig (ClientConfigurations &config)
 API call to obtain the current client configuration.
void getFingerPositions (FingerAngles &fingers)
 API call to obtain the current finger positions.
void getJointAngles (JacoAngles &angles)
 API call to obtain the current angular position of all the joints.
void getQuickStatus (QuickStatus &quick_status)
 API call to obtain the current "quick status".
void homeArm (void)
 Send the arm to the "home" position.
void initFingers (void)
 Initialize finger actuators.
bool isHomed (void)
 Determines whether the arm has returned to its "Home" state.
bool isStopped ()
 JacoComm (const ros::NodeHandle &node_handle, boost::recursive_mutex &api_mutex, const bool is_movement_on_start)
int numFingers ()
void printAngles (const JacoAngles &angles)
 Dumps the current joint angles onto the screen.
void printConfig (const ClientConfigurations &config)
 Dumps the client configuration onto the screen.
void printFingers (const FingersPosition &fingers)
 Dumps the current finger positions onto the screen.
void printPosition (const JacoPose &position)
 Dumps the current cartesian positions onto the screen.
void setCartesianPosition (const JacoPose &position, int timeout=0, bool push=true)
 Sends a cartesian coordinate trajectory to the Jaco arm.
void setCartesianVelocities (const CartesianInfo &velocities)
 Set the cartesian velocity of the tool tip.
void setConfig (const ClientConfigurations &config)
 Obtains the current arm configuration.
void setFingerPositions (const FingerAngles &fingers, int timeout=0, bool push=true)
 Sets the finger positions.
void setJointAngles (const JacoAngles &angles, int timeout=0, bool push=true)
 Sends a joint angle command to the Jaco arm.
void setJointVelocities (const AngularInfo &joint_vel)
 Set the angular velocity of the joints.
void startAPI ()
void stopAPI ()
 ~JacoComm ()

Private Attributes

boost::recursive_mutex & api_mutex_
bool is_software_stop_
jaco::JacoAPI jaco_api_
int num_fingers_

Detailed Description

Definition at line 60 of file jaco_comm.h.


Constructor & Destructor Documentation

jaco::JacoComm::JacoComm ( const ros::NodeHandle node_handle,
boost::recursive_mutex &  api_mutex,
const bool  is_movement_on_start 
)

Definition at line 55 of file jaco_comm.cpp.

Definition at line 166 of file jaco_comm.cpp.


Member Function Documentation

API call to obtain the current cartesian position of the arm.

Definition at line 525 of file jaco_comm.cpp.

API call to obtain the current client configuration.

Definition at line 568 of file jaco_comm.cpp.

API call to obtain the current finger positions.

Definition at line 544 of file jaco_comm.cpp.

API call to obtain the current angular position of all the joints.

Definition at line 506 of file jaco_comm.cpp.

void jaco::JacoComm::getQuickStatus ( QuickStatus quick_status)

API call to obtain the current "quick status".

Definition at line 584 of file jaco_comm.cpp.

void jaco::JacoComm::homeArm ( void  )

Send the arm to the "home" position.

The code replicates the function of the "home" button on the user controller by "pressing" the home button long enough for the arm to return to the home position.

Fingers are homed by manually opening them fully, then returning them to a half-open position.

Definition at line 205 of file jaco_comm.cpp.

void jaco::JacoComm::initFingers ( void  )

Initialize finger actuators.

Move fingers to the full-open position to initialize them for use. Note, The this routine requires firmware version 5.05.x (or higher?).

Definition at line 239 of file jaco_comm.cpp.

bool jaco::JacoComm::isHomed ( void  )

Determines whether the arm has returned to its "Home" state.

Checks the current joint angles, then compares them to the known "Home" joint angles.

Definition at line 179 of file jaco_comm.cpp.

Definition at line 700 of file jaco_comm.cpp.

Definition at line 633 of file jaco_comm.cpp.

void jaco::JacoComm::printAngles ( const JacoAngles angles)

Dumps the current joint angles onto the screen.

Definition at line 642 of file jaco_comm.cpp.

Dumps the client configuration onto the screen.

Definition at line 676 of file jaco_comm.cpp.

void jaco::JacoComm::printFingers ( const FingersPosition fingers)

Dumps the current finger positions onto the screen.

Definition at line 666 of file jaco_comm.cpp.

void jaco::JacoComm::printPosition ( const JacoPose position)

Dumps the current cartesian positions onto the screen.

Definition at line 653 of file jaco_comm.cpp.

void jaco::JacoComm::setCartesianPosition ( const JacoPose position,
int  timeout = 0,
bool  push = true 
)

Sends a cartesian coordinate trajectory to the Jaco arm.

Waits until the arm has stopped moving before releasing control of the API.

Definition at line 306 of file jaco_comm.cpp.

Set the cartesian velocity of the tool tip.

Definition at line 456 of file jaco_comm.cpp.

Obtains the current arm configuration.

This is the configuration which are stored on the arm itself. Many of these configurations may be set using the Windows interface.

Definition at line 492 of file jaco_comm.cpp.

void jaco::JacoComm::setFingerPositions ( const FingerAngles fingers,
int  timeout = 0,
bool  push = true 
)

Sets the finger positions.

Definition at line 363 of file jaco_comm.cpp.

void jaco::JacoComm::setJointAngles ( const JacoAngles angles,
int  timeout = 0,
bool  push = true 
)

Sends a joint angle command to the Jaco arm.

Waits until the arm has stopped moving before releasing control of the API.

Definition at line 257 of file jaco_comm.cpp.

void jaco::JacoComm::setJointVelocities ( const AngularInfo joint_vel)

Set the angular velocity of the joints.

Definition at line 424 of file jaco_comm.cpp.

Definition at line 615 of file jaco_comm.cpp.

Definition at line 596 of file jaco_comm.cpp.


Member Data Documentation

boost::recursive_mutex& jaco::JacoComm::api_mutex_ [private]

Definition at line 92 of file jaco_comm.h.

Definition at line 94 of file jaco_comm.h.

Definition at line 93 of file jaco_comm.h.

Definition at line 95 of file jaco_comm.h.


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


jaco_driver
Author(s): Ilia Baranov (Clearpath) , Jeff Schmidt (Clearpath) , Alex Bencz (Clearpath) , Matt DeDonato (WPI), Braden Stenning
autogenerated on Mon Mar 2 2015 16:21:03