ScorbotI Class Reference

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

List of all members.

Public Member Functions

 ScorbotI (OptionManager &mgr, const std::string &descrName="ScorbotServer", const std::string &tagName="ScorbotServer")
void init ()
Robots::ArmPos getIK (float x, float y, float z, const Ice::Current &)
 Get the inverse kinematics.
bool getEFpos (float &x, float &y, float &z, const Ice::Current &)
 Set the end effector position in x,y,z.
bool setEFPos (float x, float y, float z, const Ice::Current &)
 get the end effector position in x,y,z
bool setMotor (Robots::JOINTS joint, int pwm, const Ice::Current &)
 Set the motor pwm.
int getPWM (Robots::JOINTS j, const Ice::Current &)
 Get the current pwm value.
bool setJointPos (Robots::JOINTS joint, int pos, const Ice::Current &)
 Set the joint to a given position.
int getJointPos (Robots::JOINTS joint, const Ice::Current &)
 Get the joint position.
float getEncoderAng (Robots::JOINTS joint, const Ice::Current &)
 Get the anguler joint position.
void resetEncoders (const Ice::Current &)
 Reset all encoders to 0.
void stopAllMotors (const Ice::Current &)
 Stop eveything.
void setSafety (bool val, const Ice::Current &)
void homeMotor (Robots::JOINTS joint, int LimitSeekSpeed, int MSJumpSpeed, float MSJumpDelay, int MSSeekSpeed, bool MSStopCondition, bool checkMS, const Ice::Current &)
 Home Joint.
void homeMotors (const Ice::Current &)
 Home All Joints.
int getMicroSwitch (const Ice::Current &)
 Get the microSwitch states.
int getMicroSwitchMotor (Robots::JOINTS m, const Ice::Current &)
 Get the microswitch to a spacific joint.
void shutdown (const Ice::Current &)
 Shutdown.
void motorsOn (const Ice::Current &)
void motorsOff (const Ice::Current &)
double enc2ang (int encoderTicks, const Ice::Current &)
 Convert encoder tics to angle.
int ang2enc (double degrees, const Ice::Current &)
 Convert angle to encoder ticks.
double enc2mm (int encoderTicks, const Ice::Current &)
 Convert encoder ticks to mm.
int mm2enc (double mm, const Ice::Current &)
 Convert mm to encoder tics.
bool setArmPos (const Robots::ArmPos &pos, const Ice::Current &)
Robots::ArmPos getArmPos (const Ice::Current &)
std::string getPort ()
void prepareForExit ()
 ScorbotI (OptionManager &mgr, const std::string &descrName="ScorbotServer", const std::string &tagName="ScorbotServer")
ScorbotInterface::encoderVals_t encoderValsType2encoderVals_t (ScorbotIce::encoderValsType encodersT)
ScorbotIce::encoderValsType encoderVals_t2encoderValsType (ScorbotInterface::encoderVals_t encoders_t)
ScorbotIce::pwmValsType pwmVals_t2pwmValsType (ScorbotInterface::pwmVals_t pwms_t)
void init ()
void setJoint (ScorbotIce::JointType joint, int encoderPos, int timeMS, const Ice::Current &)
 Set the joint to move to the given encoder position in the given amount of time.
void setJoints (const ScorbotIce::encoderValsType &pos, int timeMS, const Ice::Current &)
 A convenience function to set multiple joint positions.
int getEncoder (ScorbotIce::JointType joint, const Ice::Current &)
 Get the position of a joint.
ScorbotIce::encoderValsType getEncoders (const Ice::Current &)
 Get the position of all joints.
void setEnabled (bool enabled, const Ice::Current &)
 Turn on/off the motors at the Scorpower box.
void resetEncoders (const Ice::Current &)
 Reset all encoders to 0, and set the desired position of all joints to 0.
float getPWM (ScorbotIce::JointType joint, const Ice::Current &)
 Get the current PWM value of a joint.
ScorbotIce::pwmValsType getPWMs (const Ice::Current &)
 Get the current PWM values of all joints.
void setControlParams (ScorbotIce::JointType joint, float pGain, float iGain, float dGain, float maxI, float maxPWM, float pwmOffset, const Ice::Current &)
 Set the PID control params for a joint.
void getPIDVals (ScorbotIce::JointType joint, float &pGain, float &iGain, float &dGain, float &maxI, float &maxPWM, float &pwmOffset, const Ice::Current &)
 Get the PID values for a joint from the microcontroller.
void getTuningVals (ScorbotIce::JointType joint, int &targetPos, int &targetVel, float &gravityCompensation, const Ice::Current &)
 Get the current target position and velocity.
void setGravityParameters (int upperArmMass, int foreArmMass, float compensationScale, const Ice::Current &)
 Set the gravity compensation parameters.
void getGravityParameters (int &upperArmMass, int &foreArmMass, float &compensationScale, const Ice::Current &)
 Get the current gravity compensation parameters.
std::string getPort ()
 Get the requested port number.
void prepareForExit ()

Detailed Description

Definition at line 17 of file app-ScorbotServer.C.


Member Function Documentation

int ScorbotI::ang2enc ( double  degrees,
const Ice::Current &   
) [inline]

Convert angle to encoder ticks.

Definition at line 215 of file app-ScorbotServer.C.

double ScorbotI::enc2ang ( int  encoderTicks,
const Ice::Current &   
) [inline]

Convert encoder tics to angle.

Definition at line 208 of file app-ScorbotServer.C.

double ScorbotI::enc2mm ( int  encoderTicks,
const Ice::Current &   
) [inline]

Convert encoder ticks to mm.

Definition at line 222 of file app-ScorbotServer.C.

bool ScorbotI::getEFpos ( float &  x,
float &  y,
float &  z,
const Ice::Current &   
) [inline]

Set the end effector position in x,y,z.

Definition at line 71 of file app-ScorbotServer.C.

int ScorbotI::getEncoder ( ScorbotIce::JointType  joint,
const Ice::Current &   
) [inline]

Get the position of a joint.

Definition at line 99 of file app-ScorbotServer.C.

float ScorbotI::getEncoderAng ( Robots::JOINTS  joint,
const Ice::Current &   
) [inline]

Get the anguler joint position.

Definition at line 122 of file app-ScorbotServer.C.

ScorbotIce::encoderValsType ScorbotI::getEncoders ( const Ice::Current &   )  [inline]

Get the position of all joints.

Definition at line 104 of file app-ScorbotServer.C.

void ScorbotI::getGravityParameters ( int &  upperArmMass,
int &  foreArmMass,
float &  compensationScale,
const Ice::Current &   
) [inline]

Get the current gravity compensation parameters.

Definition at line 151 of file app-ScorbotServer.C.

Robots::ArmPos ScorbotI::getIK ( float  x,
float  y,
float  z,
const Ice::Current &   
) [inline]

Get the inverse kinematics.

Definition at line 49 of file app-ScorbotServer.C.

int ScorbotI::getJointPos ( Robots::JOINTS  joint,
const Ice::Current &   
) [inline]

Get the joint position.

Definition at line 114 of file app-ScorbotServer.C.

int ScorbotI::getMicroSwitch ( const Ice::Current &   )  [inline]

Get the microSwitch states.

Definition at line 172 of file app-ScorbotServer.C.

int ScorbotI::getMicroSwitchMotor ( Robots::JOINTS  m,
const Ice::Current &   
) [inline]

Get the microswitch to a spacific joint.

Definition at line 180 of file app-ScorbotServer.C.

void ScorbotI::getPIDVals ( ScorbotIce::JointType  joint,
float &  pGain,
float &  iGain,
float &  dGain,
float &  maxI,
float &  maxPWM,
float &  pwmOffset,
const Ice::Current &   
) [inline]

Get the PID values for a joint from the microcontroller.

Definition at line 135 of file app-ScorbotServer.C.

std::string ScorbotI::getPort (  )  [inline]

Get the requested port number.

Definition at line 156 of file app-ScorbotServer.C.

References OModelParam< T >::getVal().

float ScorbotI::getPWM ( ScorbotIce::JointType  joint,
const Ice::Current &   
) [inline]

Get the current PWM value of a joint.

Definition at line 119 of file app-ScorbotServer.C.

int ScorbotI::getPWM ( Robots::JOINTS  j,
const Ice::Current &   
) [inline]

Get the current pwm value.

Definition at line 98 of file app-ScorbotServer.C.

ScorbotIce::pwmValsType ScorbotI::getPWMs ( const Ice::Current &   )  [inline]

Get the current PWM values of all joints.

Definition at line 124 of file app-ScorbotServer.C.

void ScorbotI::getTuningVals ( ScorbotIce::JointType  joint,
int &  targetPos,
int &  targetVel,
float &  gravityCompensation,
const Ice::Current &   
) [inline]

Get the current target position and velocity.

Definition at line 140 of file app-ScorbotServer.C.

void ScorbotI::homeMotor ( Robots::JOINTS  joint,
int  LimitSeekSpeed,
int  MSJumpSpeed,
float  MSJumpDelay,
int  MSSeekSpeed,
bool  MSStopCondition,
bool  checkMS,
const Ice::Current &   
) [inline]

Home Joint.

Definition at line 153 of file app-ScorbotServer.C.

void ScorbotI::homeMotors ( const Ice::Current &   )  [inline]

Home All Joints.

Definition at line 164 of file app-ScorbotServer.C.

int ScorbotI::mm2enc ( double  mm,
const Ice::Current &   
) [inline]

Convert mm to encoder tics.

Definition at line 229 of file app-ScorbotServer.C.

void ScorbotI::resetEncoders ( const Ice::Current &   )  [inline]

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

Definition at line 114 of file app-ScorbotServer.C.

void ScorbotI::resetEncoders ( const Ice::Current &   )  [inline]

Reset all encoders to 0.

Definition at line 130 of file app-ScorbotServer.C.

void ScorbotI::setControlParams ( ScorbotIce::JointType  joint,
float  pGain,
float  iGain,
float  dGain,
float  maxI,
float  maxPWM,
float  pwmOffset,
const Ice::Current &   
) [inline]

Set the PID control params for a joint.

Definition at line 129 of file app-ScorbotServer.C.

bool ScorbotI::setEFPos ( float  x,
float  y,
float  z,
const Ice::Current &   
) [inline]

get the end effector position in x,y,z

Definition at line 80 of file app-ScorbotServer.C.

void ScorbotI::setEnabled ( bool  enabled,
const Ice::Current &   
) [inline]

Turn on/off the motors at the Scorpower box.

Definition at line 109 of file app-ScorbotServer.C.

void ScorbotI::setGravityParameters ( int  upperArmMass,
int  foreArmMass,
float  compensationScale,
const Ice::Current &   
) [inline]

Set the gravity compensation parameters.

Definition at line 146 of file app-ScorbotServer.C.

void ScorbotI::setJoint ( ScorbotIce::JointType  joint,
int  encoderPos,
int  timeMS,
const Ice::Current &   
) [inline]

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

Definition at line 88 of file app-ScorbotServer.C.

bool ScorbotI::setJointPos ( Robots::JOINTS  joint,
int  pos,
const Ice::Current &   
) [inline]

Set the joint to a given position.

Definition at line 106 of file app-ScorbotServer.C.

void ScorbotI::setJoints ( const ScorbotIce::encoderValsType pos,
int  timeMS,
const Ice::Current &   
) [inline]

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 94 of file app-ScorbotServer.C.

bool ScorbotI::setMotor ( Robots::JOINTS  joint,
int  pwm,
const Ice::Current &   
) [inline]

Set the motor pwm.

Definition at line 90 of file app-ScorbotServer.C.

void ScorbotI::shutdown ( const Ice::Current &   )  [inline]

Shutdown.

Definition at line 188 of file app-ScorbotServer.C.

void ScorbotI::stopAllMotors ( const Ice::Current &   )  [inline]

Stop eveything.

Definition at line 138 of file app-ScorbotServer.C.


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