KinovaTypes.h
Go to the documentation of this file.
00001 
00002 #ifndef KINOVA_TYPES_H_
00003 #define KINOVA_TYPES_H_
00004 
00005 
00006 #define JOYSTICK_BUTTON_COUNT 16
00007 #define NB_ADVANCE_RETRACT_POSITION             20
00008 
00009 enum POSITION_TYPE
00010 {
00011         NOMOVEMENT_POSITION,
00012         CARTESIAN_POSITION,
00013         ANGULAR_POSITION,
00014         RETRACTED_POSITION,
00015         PREDEFINED_POSITION_1,
00016         PREDEFINED_POSITION_2,
00017         PREDEFINED_POSITION_3,
00018         CARTESIAN_VELOCITY,
00019         ANGULAR_VELOCITY,
00020         PREDEFINED_POSITION_4,
00021         PREDEFINED_POSITION_5,
00022         ANY_TRAJECTORY,
00023         TIME_DELAY,
00024 };
00025 
00026 enum HAND_MODE
00027 {
00028         HAND_NOMOVEMENT,
00029         POSITION_MODE,
00030         VELOCITY_MODE,
00031     NO_FINGER,
00032     ONE_FINGER,
00033     TWO_FINGER,
00034     THREEFINGER
00035 };
00036 
00037 enum ArmLaterality
00038 {
00039         RIGHTHAND,
00040         LEFTHAND,
00041 };
00042 
00043 struct AngularInfo
00044 {
00045         float Actuator1;
00046         float Actuator2;
00047         float Actuator3;
00048         float Actuator4;
00049         float Actuator5;
00050         float Actuator6;
00051 };
00052 
00053 struct CartesianInfo
00054 {
00055         float X;
00056         float Y;
00057         float Z;
00058         float ThetaX;
00059         float ThetaY;
00060         float ThetaZ;
00061 };
00062 
00063 struct SensorsInfo
00064 {
00065         float Voltage;
00066         float Current;
00067         float AccelerationX;
00068         float AccelerationY;
00069         float AccelerationZ;
00070         float ActuatorTemp1;
00071         float ActuatorTemp2;
00072         float ActuatorTemp3;
00073         float ActuatorTemp4;
00074         float ActuatorTemp5;
00075         float ActuatorTemp6;
00076         float FingerTemp1;
00077         float FingerTemp2;
00078         float FingerTemp3;
00079 };
00080 
00081 struct FingersPosition
00082 {
00083         float Finger1;
00084         float Finger2;
00085         float Finger3;
00086 };
00087 
00088 struct CartesianPosition
00089 {
00090         CartesianInfo Coordinates;
00091         FingersPosition Fingers;
00092 };
00093 
00094 struct AngularPosition
00095 {
00096         AngularInfo Actuators;
00097         FingersPosition Fingers;
00098 };
00099 
00100 struct Limitation
00101 {
00102         float speedParameter1;
00103         float speedParameter2;
00104         float speedParameter3;
00105         float forceParameter1;
00106         float forceParameter2;
00107         float forceParameter3;
00108         float accelerationParameter1;
00109         float accelerationParameter2;
00110         float accelerationParameter3;
00111 };
00112 
00113 struct UserPosition
00114 {
00115         POSITION_TYPE Type;
00116         float Delay;
00117     CartesianInfo CartesianPosition;
00118         AngularInfo Actuators;
00119 
00120         HAND_MODE HandMode;
00121         FingersPosition Fingers;    
00122 };
00123 
00124 struct TrajectoryPoint
00125 {
00126         UserPosition Position;
00127         int LimitationsActive;
00128         Limitation Limitations;
00129 };
00130 
00131 struct TrajectoryFIFO
00132 {
00133         unsigned int TrajectoryCount;
00134         float UsedPercentage;
00135         unsigned int MaxSize;
00136 };
00137 
00138 struct SingularityVector
00139 {
00140         int TranslationSingularityCount;
00141         int OrientationSingularityCount;
00142         float TranslationSingularityDistance;
00143         float OrientationSingularityDistance;
00144         CartesianInfo RepulsionVector;
00145 };
00146 
00147 struct JoystickCommand
00148 {
00149         short ButtonValue[JOYSTICK_BUTTON_COUNT];
00150 
00151         float InclineLeftRight;
00152     float InclineForwardBackward;
00153     float Rotate;
00154 
00155     float MoveLeftRight;
00156     float MoveForwardBackward;
00157         float PushPull;
00158 };
00159 
00160 
00161 
00162 struct ClientConfigurations
00163 {
00164     char ClientID[20];
00165     char ClientName[20];
00166         char Organization[20];
00167 
00168     char Serial[20];
00169     char Model[20];
00170 
00171         ArmLaterality Laterality;
00172 
00173     float MaxLinearSpeed;
00174         float MaxAngularSpeed;
00175     float MaxLinearAcceleration;
00176         float MaxAngularAcceleration;
00177         float MaxForce;
00178     float Sensibility;
00179         float DrinkingHeight;
00180 
00181         int ComplexRetractActive;
00182         float RetractedPositionAngle;
00183         int RetractedPositionCount;
00184         UserPosition RetractPositions[NB_ADVANCE_RETRACT_POSITION];
00185 
00186         float DrinkingDistance;
00187         int Fingers2and3Inverted;
00188         float DrinkingLenght;
00189 
00190         int DeletePreProgrammedPositionsAtRetract;
00191 
00192         int EnableFlashErrorLog;
00193         int EnableFlashPositionLog;
00194 };                      
00195 
00196 #endif /* KINOVA_TYPES_H_ */
00197 


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