Scorbot Class Reference

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

List of all members.

Classes

struct  ArmPos
struct  ArmVelParam
struct  VelParam

Public Member Functions

 Scorbot (OptionManager &mgr, const std::string &descrName="Scorbot", const std::string &tagName="Scorbot", const char *defdev="/dev/ttyUSB0")
void start2 ()
 do some additional config at start time; see ModelComponent.H
void stop1 ()
 This is called from within stop() before the subcomponents stop.
bool setMotor (MOTOR m, int pwm)
 Set the Motor Speed and Direction by pwm.
void setMotorPos (MOTOR m, int pos)
 Set the Motor Position by the encoder value.
bool setJointPos (MOTOR joint, int position, bool relative=false, int duration=2000)
int getEncoder (MOTOR m)
 Get the encoder value from motor.
float getEncoderAng (MOTOR m)
int getPWM (MOTOR m)
bool resetEncoders ()
 Reset all motor encoder value to 0.
void resetMotorPos (void)
 Reset all motor position to the home place.
bool stopAllMotors ()
 Stop all the motor movement.
void simLoop ()
void setSafety (bool val)
void getEF_pos (float &x, float &y, float &z)
void homeMotors ()
void homeMotor (RobotArm::MOTOR axis, int LimitSeekSpeed, int MSJumpSpeed, float MSJumpDelay, int MSSeekSpeed, bool MSStopCondition, bool checkMS)
bool motorsOff ()
bool motorsOn ()
int getMicroSwitch ()
char * getMicroSwitchByte ()
bool getMicroSwitchMotor (RobotArm::MOTOR m)
void tunePID (MOTOR m, float p, float i, float d, bool relative)
void stopControl ()
void startControl ()
bool controlStoped ()
double enc2ang (int encoderTicks)
int ang2enc (double degrees)
double enc2mm (int encoderTicks)
int mm2enc (double mm)
void controlLoop ()
void setArmPos (ArmPos &armPos)
ArmPos getArmPos ()
ArmPos readArmState ()
Point3D< float > getEFPos (const ArmPos &armPos)
 Get the End Effector pos.
ArmPos getIKArmPos (const Point3D< float > &efPos)
 Get the arm position from desired end effector posision.
bool set3DPos (bool relative=false, int duration=2000)
double gravityComp (int sholderPos, int elbowPos)
 gravity compensator
ArmPos getDesiredArmPos ()
int getJointPos (MOTOR m)
bool moveDone ()
bool setInternalPIDGain (MOTOR m, int P, int I, int D)
bool setInternalPos (ArmPos pos)
bool internalPidEn ()
int write (const void *buffer, const int nbytes)
int read (void *buffer, const int nbytes)
void shutdownMotorsOff (bool val)
uint8_t readMicroswitches ()
uint8_t readMicroswitch (uint8_t motor_index)
long readEncoder (uint8_t motor_index)
float readPWMDuty (uint8_t motor_index)
uint8_t readControllerStatus ()
uint8_t * readControlParameters (uint8_t motor_index, uint8_t &length)
long readTargetPosition (uint8_t motor_index)
long readTargetVelocity (uint8_t motor_index)
void resetEncoders ()
 Reset all motor encoder value to 0.
void setDestination (uint8_t motor_index, long position, long duration)
bool setControlParameters (uint8_t motor_index, uint8_t length, uint8_t *params)
void enableMotors ()
void disableMotors ()

Detailed Description

Definition at line 78 of file Scorbot.H.


Member Function Documentation

Point3D< float > Scorbot::getEFPos ( const ArmPos armPos  ) 

Get the End Effector pos.

Definition at line 464 of file Scorbot.C.

References Point3D< T >::x.

int Scorbot::getEncoder ( MOTOR  m  )  [virtual]

Get the encoder value from motor.

Reimplemented from RobotArm.

Definition at line 955 of file Scorbot.C.

Scorbot::ArmPos Scorbot::getIKArmPos ( const Point3D< float > &  efPos  ) 

Get the arm position from desired end effector posision.

Definition at line 486 of file Scorbot.C.

References sqrt(), squareOf(), and Point3D< T >::x.

double Scorbot::gravityComp ( int  sholderPos,
int  elbowPos 
)

gravity compensator

Definition at line 157 of file Scorbot.C.

References sqrt(), and squareOf().

void Scorbot::resetEncoders (  )  [virtual]

Reset all motor encoder value to 0.

Reimplemented from RobotArm.

void Scorbot::resetEncoders (  )  [virtual]

Reset all motor encoder value to 0.

Reimplemented from RobotArm.

Definition at line 1099 of file Scorbot.C.

void Scorbot::resetMotorPos ( void   )  [virtual]

Reset all motor position to the home place.

Reimplemented from RobotArm.

Definition at line 1133 of file Scorbot.C.

bool Scorbot::setMotor ( MOTOR  m,
int  pwm 
) [virtual]

Set the Motor Speed and Direction by pwm.

Reimplemented from RobotArm.

Definition at line 751 of file Scorbot.C.

References abs().

void Scorbot::setMotorPos ( MOTOR  m,
int  pos 
) [virtual]

Set the Motor Position by the encoder value.

Reimplemented from RobotArm.

Definition at line 1128 of file Scorbot.C.

void Scorbot::start2 (  )  [virtual]

do some additional config at start time; see ModelComponent.H

Reimplemented from RobotArm.

Definition at line 130 of file Scorbot.C.

void Scorbot::stop1 (  )  [virtual]

This is called from within stop() before the subcomponents stop.

Reimplemented from ModelComponent.

Definition at line 139 of file Scorbot.C.

bool Scorbot::stopAllMotors (  )  [virtual]

Stop all the motor movement.

Reimplemented from RobotArm.

Definition at line 881 of file Scorbot.C.


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