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

#include <jaco_comm.h>

List of all members.

Public Member Functions

void GetAngles (JacoAngles &angles)
 API call to obtain the current angular position of all the joints.
void GetConfig (ClientConfigurations &config)
 API call to obtain the current client configuration.
void GetFingers (FingerAngles &fingers)
 API call to obtain the current finger positions.
void GetPosition (JacoPose &position)
 API call to obtain the current cartesian position of the arm.
void HomeArm (void)
 Send the arm to the "home" position.
bool HomeState (void)
 Determines whether the arm has returned to its "Home" state.
void InitializeFingers (void)
 Initialize finger actuators.
 JacoComm (JacoAngles)
void PrintAngles (JacoAngles &angles)
 Dumps the current joint angles onto the screen.
void PrintConfig (ClientConfigurations config)
 Dumps the client configuration onto the screen.
void PrintFingers (FingersPosition fingers)
 Dumps the current finger positions onto the screen.
void PrintPosition (JacoPose &position)
 Dumps the current cartesian positions onto the screen.
void SetAngles (JacoAngles &angles, int timeout=0, bool push=true)
 Sends a joint angle command to the Jaco arm.
void SetCartesianVelocities (CartesianInfo velocities)
 Set the velocity of the angles using cartesian input.
void SetConfig (ClientConfigurations config)
 Obtains the current arm configuration.
void SetFingers (FingerAngles &fingers, int timeout=0, bool push=true)
 Sets the finger positions.
void SetPosition (JacoPose &position, int timeout=0, bool push=true)
 Sends a cartesian coordinate trajectory to the Jaco arm.
void SetVelocities (AngularInfo joint_vel)
 Set the velocity of the angles using angular input.
void Start ()
void Stop ()
bool Stopped ()
 ~JacoComm ()

Private Member Functions

void WaitForHome (int)
 Wait for the arm to reach the "home" position.

Private Attributes

jaco::JacoAPIAPI
boost::recursive_mutex api_mutex
JacoAngles home_position
bool software_stop

Detailed Description

Definition at line 57 of file jaco_comm.h.


Constructor & Destructor Documentation

Definition at line 54 of file jaco_comm.cpp.

Definition at line 88 of file jaco_comm.cpp.


Member Function Documentation

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

Definition at line 324 of file jaco_comm.cpp.

API call to obtain the current client configuration.

Definition at line 365 of file jaco_comm.cpp.

API call to obtain the current finger positions.

Definition at line 352 of file jaco_comm.cpp.

void jaco::JacoComm::GetPosition ( JacoPose position)

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

Definition at line 337 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 120 of file jaco_comm.cpp.

bool jaco::JacoComm::HomeState ( 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 99 of file jaco_comm.cpp.

Initialize finger actuators.

Move fingers to open position, then close part way to initialize limits.

Definition at line 153 of file jaco_comm.cpp.

Dumps the current joint angles onto the screen.

Definition at line 375 of file jaco_comm.cpp.

Dumps the client configuration onto the screen.

Definition at line 417 of file jaco_comm.cpp.

Dumps the current finger positions onto the screen.

Definition at line 406 of file jaco_comm.cpp.

Dumps the current cartesian positions onto the screen.

Definition at line 390 of file jaco_comm.cpp.

void jaco::JacoComm::SetAngles ( 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 173 of file jaco_comm.cpp.

Set the velocity of the angles using cartesian input.

Definition at line 287 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 315 of file jaco_comm.cpp.

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

Sets the finger positions.

Definition at line 238 of file jaco_comm.cpp.

void jaco::JacoComm::SetPosition ( 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 206 of file jaco_comm.cpp.

Set the velocity of the angles using angular input.

Definition at line 265 of file jaco_comm.cpp.

Definition at line 461 of file jaco_comm.cpp.

Definition at line 442 of file jaco_comm.cpp.

Definition at line 470 of file jaco_comm.cpp.

void jaco::JacoComm::WaitForHome ( int  timeout) [private]

Wait for the arm to reach the "home" position.

Parameters:
timeoutTimeout after which to give up waiting for arm to finish "homing".

Definition at line 480 of file jaco_comm.cpp.


Member Data Documentation

Definition at line 85 of file jaco_comm.h.

boost::recursive_mutex jaco::JacoComm::api_mutex [private]

Definition at line 84 of file jaco_comm.h.

Definition at line 87 of file jaco_comm.h.

Definition at line 86 of file jaco_comm.h.


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


jaco_driver
Author(s): Jeff Schmidt (Clearpath), Alex Bencz (Clearpath), Matt DeDonato (WPI)
autogenerated on Mon Jan 6 2014 11:23:43