Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
ManusArm Class Reference

Singleton class representing the ARM.

More...

#include <ManusArm.hpp>

List of all members.

Public Member Functions

void fold ()
 Folds the ARM.
std::string getCsvState ()
 Returns the ARM's current position as a CSV string.
void getPosition (float position[])
 Gets current ARM position.
std::string getPrintState ()
 Returns the ARM's current position as a printable string.
int init (std::string interface)
 Inits the ARM.
bool isMoveComplete ()
void moveCartesian (const CartesianMove &cmd)
 Binds the cartesian movement method and the movement command to a thread.
void moveConstant (const ConstantMove &cmd)
 Binds the constant movement method and the movement command to a thread.
void setMoveComplete (bool move_complete)
void unfold ()
 Unfolds the ARM.

Static Public Member Functions

static ManusArminstance ()
 Returns the ARM instance.

Private Member Functions

void doCartesianMove (const CartesianMove &cmd)
 Moves the ARM to the position specified in the message.
void doConstantMove (const ConstantMove &cmd)
 Moves the ARM in the direction specified in the message.
void enqueueFrame (can_frame toSend)
 Adds a frame to the ARM's message queue.
 ManusArm ()
 ManusArm (ManusArm const &)
ManusArmoperator= (ManusArm const &)
void pollCanSocket ()
void sendFrames (can_frame frame)
void setCartesian ()
 Puts the ARM in cartesian mode.
void setCbox (int cbox, can_frame *frm)

Private Attributes

int canSock
armState currState
boost::thread motionThread
bool moveComplete
bool running
std::vector< can_frame > sendQueue
boost::mutex stateMutex

Static Private Attributes

static ManusArmarmInstance = NULL

Detailed Description

Singleton class representing the ARM.

Author:
Abraham Shultz
Jonathan Hasenzahl

Definition at line 101 of file ManusArm.hpp.


Constructor & Destructor Documentation

ManusArm::ManusArm ( ) [private]

Definition at line 721 of file ManusArm.cpp.

ManusArm::ManusArm ( ManusArm const &  ) [inline, private]

Definition at line 106 of file ManusArm.hpp.


Member Function Documentation

void ManusArm::doCartesianMove ( const CartesianMove cmd) [private]

Moves the ARM to the position specified in the message.

The ARM will stop when it reaches its destination.

Parameters:
cmdthe cartesian movement message

Definition at line 163 of file ManusArm.cpp.

void ManusArm::doConstantMove ( const ConstantMove cmd) [private]

Moves the ARM in the direction specified in the message.

This is a constant motion; the ARM will not stop until it is told otherwise.

Parameters:
cmdthe constant movement message

Definition at line 339 of file ManusArm.cpp.

void ManusArm::enqueueFrame ( can_frame  toSend) [private]

Adds a frame to the ARM's message queue.

Parameters:
toSendthe frame to add to the queue

Definition at line 415 of file ManusArm.cpp.

void ManusArm::fold ( )

Folds the ARM.

Warning: Be sure that the ARM is free of obstructions (wires/cords, etc) when folding or else it will get stuck and will not unfold.

Definition at line 387 of file ManusArm.cpp.

Returns the ARM's current position as a CSV string.

Returns:
the ARM's current position as a CSV string

Definition at line 36 of file ManusArm.cpp.

void ManusArm::getPosition ( float  fill[])

Gets current ARM position.

Parameters:
fillarray of floats to which the ARM positions will be stored

Definition at line 19 of file ManusArm.cpp.

Returns the ARM's current position as a printable string.

Returns:
the ARM's current position as a printable string

Definition at line 78 of file ManusArm.cpp.

int ManusArm::init ( std::string  interface)

Inits the ARM.

Establishes a connection to the ARM hardware.

Definition at line 621 of file ManusArm.cpp.

ManusArm * ManusArm::instance ( ) [static]

Returns the ARM instance.

The ARM is a singleton; this method allows only one instance

Returns:
the ARM instance

Definition at line 607 of file ManusArm.cpp.

bool ManusArm::isMoveComplete ( ) [inline]

Definition at line 141 of file ManusArm.hpp.

void ManusArm::moveCartesian ( const CartesianMove cmd)

Binds the cartesian movement method and the movement command to a thread.

Call this method to move the arm with a cartesian movement message.

Parameters:
cmdthe cartesian movement message

Definition at line 151 of file ManusArm.cpp.

void ManusArm::moveConstant ( const ConstantMove cmd)

Binds the constant movement method and the movement command to a thread.

Call this method to move the arm with a constant movement message.

Parameters:
cmdthe constant movement message

Definition at line 327 of file ManusArm.cpp.

ManusArm& ManusArm::operator= ( ManusArm const &  ) [private]
void ManusArm::pollCanSocket ( ) [private]

Definition at line 452 of file ManusArm.cpp.

void ManusArm::sendFrames ( can_frame  frame) [private]
void ManusArm::setCartesian ( ) [private]

Puts the ARM in cartesian mode.

Definition at line 367 of file ManusArm.cpp.

void ManusArm::setCbox ( int  cbox,
can_frame *  frm 
) [private]
Parameters:
cbox
frm

Definition at line 123 of file ManusArm.cpp.

void ManusArm::setMoveComplete ( bool  move_complete) [inline]

Definition at line 142 of file ManusArm.hpp.

void ManusArm::unfold ( )

Unfolds the ARM.

Definition at line 400 of file ManusArm.cpp.


Member Data Documentation

ManusArm * ManusArm::armInstance = NULL [static, private]

Definition at line 109 of file ManusArm.hpp.

int ManusArm::canSock [private]

Definition at line 112 of file ManusArm.hpp.

Definition at line 117 of file ManusArm.hpp.

boost::thread ManusArm::motionThread [private]

Definition at line 131 of file ManusArm.hpp.

bool ManusArm::moveComplete [private]

Definition at line 118 of file ManusArm.hpp.

bool ManusArm::running [private]

Definition at line 113 of file ManusArm.hpp.

std::vector<can_frame> ManusArm::sendQueue [private]

Definition at line 124 of file ManusArm.hpp.

boost::mutex ManusArm::stateMutex [private]

Definition at line 119 of file ManusArm.hpp.


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


arm
Author(s): Jonathan Hasenzahl
autogenerated on Sun Jan 5 2014 11:12:32