ScorbotInterface Class Reference

Inheritance diagram for ScorbotInterface:
Inheritance graph
[legend]
Collaboration diagram for ScorbotInterface:
Collaboration graph
[legend]

List of all members.

Public Types

enum  Joint_t {
  Base = 0, Shoulder = 1, Elbow = 2, Wrist1 = 3,
  Wrist2 = 4, Gripper = 5, Slider = 6
}
typedef std::map< Joint_t, int32encoderVals_t
typedef std::map< Joint_t, float > pwmVals_t

Public Member Functions

 ScorbotInterface (OptionManager &mgr, const std::string &descrName="ScorbotInterface", const std::string &tagName="ScorbotInterface")
 ~ScorbotInterface ()
 Disables the motor interface.
void start2 ()
 Sets all desired joint positions to their current positions at startup.
void setJoint (Joint_t joint, int32 encoderPos, int32 time_ms)
 Set the joint to move to the given encoder position in the given amount of time.
void setJoints (encoderVals_t pos, int32 time_ms)
 A convenience function to set multiple joint positions.
int32 getEncoder (Joint_t joint)
 Get the position of a joint.
encoderVals_t getEncoders ()
 Get the position of all joints.
void setEnabled (bool enabled)
 Turn on/off the motors at the Scorpower box.
void resetEncoders ()
 Reset all encoders to 0, and set the desired position of all joints to 0.
float getPWM (Joint_t joint)
 Get the current PWM value of a joint.
pwmVals_t getPWMs ()
 Get the current PWM values of all joints.
void setControlParams (Joint_t joint, float pGain, float iGain, float dGain, float maxI, float maxPWM, float pwmOffset)
 Set the PID control params for a joint.
void getPIDVals (Joint_t joint, float &pGain, float &iGain, float &dGain, float &maxI, float &maxPWM, float &pwmOffset)
 Get the PID values for a joint from the microcontroller.
void getTuningVals (Joint_t joint, int32 &targetPos, int32 &targetVel, float &gravityCompensation)
 Get the current target position and velocity.
void setGravityParameters (int32 upperArmMass, int32 foreArmMass, float compensationScale)
 Set the gravity compensation parameters.
void getGravityParameters (int32 &upperArmMass, int32 &foreArmMass, float &compensationScale)
 Get the current gravity compensation parameters.

Detailed Description

Definition at line 9 of file ScorbotInterface.H.


Constructor & Destructor Documentation

ScorbotInterface::~ScorbotInterface (  ) 

Disables the motor interface.

Definition at line 80 of file ScorbotInterface.C.

References setEnabled().


Member Function Documentation

int32 ScorbotInterface::getEncoder ( ScorbotInterface::Joint_t  joint  ) 

Get the position of a joint.

Definition at line 188 of file ScorbotInterface.C.

ScorbotInterface::encoderVals_t ScorbotInterface::getEncoders (  ) 

Get the position of all joints.

Definition at line 126 of file ScorbotInterface.C.

Referenced by start2().

void ScorbotInterface::getGravityParameters ( int32 upperArmMass,
int32 foreArmMass,
float &  compensationScale 
)

Get the current gravity compensation parameters.

Definition at line 620 of file ScorbotInterface.C.

void ScorbotInterface::getPIDVals ( ScorbotInterface::Joint_t  joint,
float &  pGain,
float &  iGain,
float &  dGain,
float &  maxI,
float &  maxPWM,
float &  pwmOffset 
)

Get the PID values for a joint from the microcontroller.

Definition at line 460 of file ScorbotInterface.C.

float ScorbotInterface::getPWM ( ScorbotInterface::Joint_t  joint  ) 

Get the current PWM value of a joint.

Definition at line 218 of file ScorbotInterface.C.

ScorbotInterface::pwmVals_t ScorbotInterface::getPWMs (  ) 

Get the current PWM values of all joints.

Definition at line 248 of file ScorbotInterface.C.

void ScorbotInterface::getTuningVals ( ScorbotInterface::Joint_t  joint,
int32 targetPos,
int32 targetVel,
float &  gravityCompensation 
)

Get the current target position and velocity.

Definition at line 535 of file ScorbotInterface.C.

void ScorbotInterface::resetEncoders (  ) 

Reset all encoders to 0, and set the desired position of all joints to 0.

Definition at line 358 of file ScorbotInterface.C.

References setEnabled(), and setJoints().

void ScorbotInterface::setControlParams ( ScorbotInterface::Joint_t  joint,
float  pGain,
float  iGain,
float  dGain,
float  maxI,
float  maxPWM,
float  pwmOffset 
)

Set the PID control params for a joint.

Definition at line 395 of file ScorbotInterface.C.

Referenced by start2().

void ScorbotInterface::setEnabled ( bool  enabled  ) 

Turn on/off the motors at the Scorpower box.

Definition at line 318 of file ScorbotInterface.C.

Referenced by resetEncoders(), and ~ScorbotInterface().

void ScorbotInterface::setGravityParameters ( int32  upperArmMass,
int32  foreArmMass,
float  compensationScale 
)

Set the gravity compensation parameters.

Definition at line 583 of file ScorbotInterface.C.

void ScorbotInterface::setJoint ( ScorbotInterface::Joint_t  joint,
int32  encoderPos,
int32  time_ms 
)

Set the joint to move to the given encoder position in the given amount of time.

Definition at line 86 of file ScorbotInterface.C.

Referenced by setJoints().

void ScorbotInterface::setJoints ( ScorbotInterface::encoderVals_t  pos,
int32  time_ms 
)

A convenience function to set multiple joint positions.

This function just loops over all positions in pos and sets them using setJointPos() !

Definition at line 118 of file ScorbotInterface.C.

References setJoint().

Referenced by resetEncoders(), and start2().

void ScorbotInterface::start2 (  )  [virtual]

Sets all desired joint positions to their current positions at startup.

Reimplemented from ModelComponent.

Definition at line 16 of file ScorbotInterface.C.

References getEncoders(), setControlParams(), and setJoints().


The documentation for this class was generated from the following files:
Generated on Sun May 8 08:43:47 2011 for iLab Neuromorphic Vision Toolkit by  doxygen 1.6.3