KinovaTypes.h
Go to the documentation of this file.
00001 
00005 #pragma once
00006 
00010 #define JOYSTICK_BUTTON_COUNT 16
00011 
00015 #define NB_ADVANCE_RETRACT_POSITION             20
00016 
00020 #define ERROR_DATA_COUNT_MAX    50
00021 
00025 #define ERROR_LAYER_COUNT 7
00026 
00030 #define LEGACY_CONFIG_NB_ZONES_MAX              10
00031 
00035 #define LEGACY_CONFIG_NB_POINTS_COUNT   8
00036 
00040 #define CONTROL_MAPPING_COUNT 6
00041 
00045 #define MODE_MAP_COUNT 6
00046 
00050 #define STICK_EVENT_COUNT 6
00051 
00055 #define BUTTON_EVENT_COUNT 26
00056 
00060 #define STRING_LENGTH 20
00061 
00065 #define JACO_FINGERS_COUNT 3
00066 
00071 #define ERROR_UNKNOWFILE 5001
00072 
00077 #define ERROR_MEMORY 5002
00078 
00083 #define ERROR_FILEREADING 5003
00084 
00088 const unsigned short PAGE_SIZE = 2048;
00089 
00093 const int ADDRESS_PAGE_SIZE = 4;
00094 
00098 const unsigned short PACKET_PER_PAGE_QTY = 40;
00099 
00103 const int PAGEPACKET_SIZE = 52;
00104 
00108 const int USB_HEADER_SIZE = 8;
00109 
00113 const int USB_DATA_SIZE = 56;
00114 
00121 enum POSITION_TYPE
00122 {
00123 
00124   NOMOVEMENT_POSITION = 0, 
00125   CARTESIAN_POSITION = 1, 
00126   ANGULAR_POSITION = 2, 
00127   CARTESIAN_VELOCITY = 7, 
00128   ANGULAR_VELOCITY = 8, 
00129   ANY_TRAJECTORY = 11, 
00130   TIME_DELAY = 12, 
00131 };
00132 
00133 enum PERIPHERAL_TYPE
00134 {
00135   PERIPHERAL_TYPE_NONE = 0, 
00136   PERIPHERAL_TYPE_ANY = 1, 
00137   PERIPHERAL_TYPE_ACTUATORK01 = 100, 
00138   PERIPHERAL_TYPE_FINGERK01 = 200, 
00139   PERIPHERAL_TYPE_JOYSTICK = 300, 
00140   PERIPHERAL_TYPE_VIRTUAL_JOYSTICK = 301, 
00141   PERIPHERAL_TYPE_CAN_INTERFACE = 400, 
00142 };
00143 
00147 enum HAND_MODE
00148 {
00149   HAND_NOMOVEMENT, 
00150   POSITION_MODE, 
00151   VELOCITY_MODE, 
00152 };
00153 
00157 enum ArmLaterality
00158 {
00159   RIGHTHAND, 
00160   LEFTHAND, 
00161 };
00162 
00167 enum Controller
00168 {
00169   THREE_AXIS_JOYSTICK = 0, 
00170   TWO_AXIS_JOYSTICK = 1, 
00171   API = 2, 
00172   EASY_RIDER = 3, 
00173   UNIVERSAL_INTERFACE = 4, 
00174   EXTERNAL_CUSTOMINTERFACE = 5, 
00175   NONE = 6, 
00176   OLED_DISPLAY = 7 
00177 };
00178 
00183 enum CONTROL_TYPE
00184 {
00185   CONTROL_TYPE_CARTESIAN = 0, 
00186   CONTROL_TYPE_ANGULAR = 1 
00187 };
00188 
00192 enum CONTROL_MODULE
00193 {
00197   CONTROL_MODULE_NONE,
00198 
00202   CONTROL_MODULE_ANGULAR_VELOCITY,
00203 
00207   CONTROL_MODULE_ANGULAR_POSITION,
00208 
00213   CONTROL_MODULE_CARTESIAN_VELOCITY,
00214 
00219   CONTROL_MODULE_CARTESIAN_POSITION,
00220 
00225   CONTROL_MODULE_RETRACT,
00226 
00230   CONTROL_MODULE_TRAJECTORY,
00231 
00235   CONTROL_MODULE_PREDEFINED,
00236 
00240   CONTROL_MODULE_TIMEDELAY,
00241 };
00242 
00246 enum RETRACT_TYPE
00247 {
00251   RETRACT_TYPE_NORMAL_TO_READY = 0,
00252 
00256   RETRACT_TYPE_READY_STANDBY = 1,
00257 
00261   RETRACT_TYPE_READY_TO_RETRACT = 2,
00262 
00266   RETRACT_TYPE_RETRACT_STANDBY = 3,
00267 
00271   RETRACT_TYPE_RETRACT_TO_READY = 4,
00272 
00276   RETRACT_TYPE_NORMAL_STANDBY = 5,
00277 
00281   RETRACT_TYPE_NOT_INITIALIZED = 6
00282 };
00283 
00287 struct AngularInfo
00288 {
00294   float Actuator1;
00295 
00301   float Actuator2;
00302 
00308   float Actuator3;
00309 
00315   float Actuator4;
00316 
00322   float Actuator5;
00323 
00329   float Actuator6;
00330 
00334   void InitStruct()
00335   {
00336     Actuator1 = 0.0f;
00337     Actuator2 = 0.0f;
00338     Actuator3 = 0.0f;
00339     Actuator4 = 0.0f;
00340     Actuator5 = 0.0f;
00341     Actuator6 = 0.0f;
00342   }
00343 };
00344 
00348 struct CartesianInfo
00349 {
00355   float X;
00356 
00362   float Y;
00363 
00369   float Z;
00370 
00377   float ThetaX;
00378 
00384   float ThetaY;
00385 
00391   float ThetaZ;
00392 
00396   void InitStruct()
00397   {
00398     X = 0.0f;
00399     Y = 0.0f;
00400     Z = 0.0f;
00401     ThetaX = 0.0f;
00402     ThetaY = 0.0f;
00403     ThetaZ = 0.0f;
00404   }
00405 };
00406 
00412 struct SensorsInfo
00413 {
00417   float Voltage;
00418 
00422   float Current;
00423 
00427   float AccelerationX;
00428 
00432   float AccelerationY;
00433 
00437   float AccelerationZ;
00438 
00442   float ActuatorTemp1;
00443 
00447   float ActuatorTemp2;
00448 
00452   float ActuatorTemp3;
00453 
00457   float ActuatorTemp4;
00458 
00462   float ActuatorTemp5;
00463 
00467   float ActuatorTemp6;
00468 
00472   float FingerTemp1;
00473 
00477   float FingerTemp2;
00478 
00482   float FingerTemp3;
00483 
00487   void InitStruct()
00488   {
00489     Voltage = 0.0f;
00490     Current = 0.0f;
00491     AccelerationX = 0.0f;
00492     AccelerationY = 0.0f;
00493     AccelerationZ = 0.0f;
00494     ActuatorTemp1 = 0.0f;
00495     ActuatorTemp2 = 0.0f;
00496     ActuatorTemp3 = 0.0f;
00497     ActuatorTemp4 = 0.0f;
00498     ActuatorTemp5 = 0.0f;
00499     ActuatorTemp6 = 0.0f;
00500     FingerTemp1 = 0.0f;
00501     FingerTemp2 = 0.0f;
00502     FingerTemp3 = 0.0f;
00503   }
00504 
00505 };
00506 
00510 struct FingersPosition
00511 {
00515   float Finger1;
00516 
00520   float Finger2;
00521 
00525   float Finger3;
00526 
00530   void InitStruct()
00531   {
00532     Finger1 = 0.0f;
00533     Finger2 = 0.0f;
00534     Finger3 = 0.0f;
00535   }
00536 };
00537 
00545 struct CartesianPosition
00546 {
00550   CartesianInfo Coordinates;
00551 
00555   FingersPosition Fingers;
00556 
00560   void InitStruct()
00561   {
00562     Coordinates.InitStruct();
00563     Fingers.InitStruct();
00564   }
00565 };
00566 
00570 struct AngularPosition
00571 {
00575   AngularInfo Actuators;
00576 
00580   FingersPosition Fingers;
00581 };
00582 
00589 struct Limitation
00590 {
00594   float speedParameter1;
00595 
00599   float speedParameter2;
00600   float speedParameter3; 
00601   float forceParameter1; 
00602   float forceParameter2; 
00603   float forceParameter3; 
00604   float accelerationParameter1; 
00605   float accelerationParameter2; 
00606   float accelerationParameter3; 
00608   void InitStruct()
00609   {
00610     speedParameter1 = 0.0f;
00611     speedParameter2 = 0.0f;
00612     speedParameter3 = 0.0f;
00613     forceParameter1 = 0.0f;
00614     forceParameter2 = 0.0f;
00615     forceParameter3 = 0.0f;
00616     accelerationParameter1 = 0.0f;
00617     accelerationParameter2 = 0.0f;
00618     accelerationParameter3 = 0.0f;
00619   }
00620 };
00621 
00626 struct UserPosition
00627 {
00631   POSITION_TYPE Type;
00632 
00636   float Delay;
00637 
00641   CartesianInfo CartesianPosition;
00642 
00646   AngularInfo Actuators;
00647 
00651   HAND_MODE HandMode;
00652 
00656   FingersPosition Fingers;
00657 
00658   void InitStruct()
00659   {
00660     Type = CARTESIAN_POSITION;
00661     Delay = 0.0f;
00662     CartesianPosition.InitStruct();
00663     Actuators.InitStruct();
00664     HandMode = POSITION_MODE;
00665     Fingers.InitStruct();
00666   }
00667 };
00668 
00672 struct TrajectoryPoint
00673 {
00677   UserPosition Position;
00678 
00682   int LimitationsActive;
00683 
00687   Limitation Limitations;
00688 
00689   void InitStruct()
00690   {
00691     Position.InitStruct();
00692     LimitationsActive = 0;
00693     Limitations.InitStruct();
00694   }
00695 };
00696 
00700 struct TrajectoryFIFO
00701 {
00705   unsigned int TrajectoryCount;
00706 
00710   float UsedPercentage;
00711 
00715   unsigned int MaxSize;
00716 };
00717 
00722 struct SingularityVector
00723 {
00724   int TranslationSingularityCount;
00725   int OrientationSingularityCount;
00726   float TranslationSingularityDistance;
00727   float OrientationSingularityDistance;
00728   CartesianInfo RepulsionVector;
00729 };
00730 
00734 struct JoystickCommand
00735 {
00739   short ButtonValue[JOYSTICK_BUTTON_COUNT];
00740 
00745   float InclineLeftRight;
00746 
00751   float InclineForwardBackward;
00752 
00757   float Rotate;
00758 
00763   float MoveLeftRight;
00764 
00769   float MoveForwardBackward;
00770 
00775   float PushPull;
00776 
00777   void InitStruct()
00778   {
00779     for (int i = 0; i < JOYSTICK_BUTTON_COUNT; i++)
00780     {
00781       ButtonValue[i] = 0;
00782     }
00783 
00784     InclineLeftRight = 0.0f;
00785     InclineForwardBackward = 0.0f;
00786     Rotate = 0.0f;
00787     MoveLeftRight = 0.0f;
00788     MoveForwardBackward = 0.0f;
00789     PushPull = 0.0f;
00790   }
00791 };
00792 
00801 struct ClientConfigurations
00802 {
00806   char ClientID[STRING_LENGTH];
00807 
00811   char ClientName[STRING_LENGTH];
00812 
00816   char Organization[STRING_LENGTH];
00817 
00821   char Serial[STRING_LENGTH];
00822 
00826   char Model[STRING_LENGTH];
00827 
00832   ArmLaterality Laterality;
00833 
00837   float MaxTranslationVelocity;
00838 
00842   float MaxOrientationVelocity;
00843 
00847   float MaxTranslationAcceleration;
00848 
00852   float MaxOrientationAcceleration;
00853 
00857   float MaxForce;
00858 
00864   float Sensibility;
00865 
00870   float DrinkingHeight;
00871 
00877   int ComplexRetractActive;
00878 
00882   float RetractedPositionAngle;
00883 
00887   int RetractedPositionCount;
00888   UserPosition RetractPositions[NB_ADVANCE_RETRACT_POSITION];
00889 
00894   float DrinkingDistance;
00895 
00899   int Fingers2and3Inverted;
00900 
00905   float DrinkingLenght;
00906 
00910   int DeletePreProgrammedPositionsAtRetract;
00911 
00915   int EnableFlashErrorLog;
00916 
00920   int EnableFlashPositionLog;
00921 
00925   int Expansion[198];
00926 };
00927 
00933 enum ControlFunctionalityTypeEnum
00934 {
00938   CF_NoFunctionality = 0,
00939 
00943   CF_Disable_EnableJoystick = 1,
00944 
00951   CF_Retract_ReadyToUse = 2,
00952 
00956   CF_Change_TwoAxis_ThreeAxis = 3,
00957 
00961   CF_Change_DrinkingMode = 4,
00962 
00966   CF_Cycle_ModeA_list = 5,
00967 
00971   CF_Cycle_ModeB_list = 6,
00972 
00976   CF_DecreaseSpeed = 7,
00977 
00981   CF_IncreaseSpeed = 8,
00982 
00986   CF_Goto_Position1 = 9,
00987 
00991   CF_Goto_Position2 = 10,
00992 
00996   CF_Goto_Position3 = 11,
00997 
01001   CF_Goto_Position4 = 12,
01002 
01006   CF_Goto_Position5 = 13,
01007 
01011   CF_RecordPosition1 = 14,
01012 
01016   CF_RecordPosition2 = 15,
01017 
01021   CF_RecordPosition3 = 16,
01022 
01026   CF_RecordPosition4 = 17,
01027 
01031   CF_RecordPosition5 = 18,
01032 
01037   CF_X_Positive = 19,
01038 
01043   CF_X_Negative = 20,
01044 
01049   CF_Y_Positive = 21,
01050 
01055   CF_Y_Negative = 22,
01056 
01061   CF_Z_Positive = 23,
01062 
01067   CF_Z_Negative = 24,
01068 
01073   CF_R_Positive = 25,
01074 
01079   CF_R_Negative = 26,
01080 
01085   CF_U_Positive = 27,
01086 
01091   CF_U_Negative = 28,
01092 
01097   CF_V_Positive = 29,
01098 
01103   CF_V_Negative = 30,
01104 
01108   CF_OpenHandOneFingers = 31,
01109 
01113   CF_CloseHandOneFingers = 32,
01114 
01118   CF_OpenHandTwoFingers = 33,
01119 
01123   CF_CloseHandTwoFingers = 34,
01124 
01128   CF_OpenHandThreeFingers = 35,
01129 
01133   CF_CloseHandThreeFingers = 36,
01134 
01138   CF_ForceAngularVelocity = 37,
01139 
01143   CF_ForceControlStatus = 38,
01144 
01145   CF_Trajectory = 39,
01146 
01150   CF_AutomaticOrientationXPlus = 40,
01151 
01155   CF_AutomaticOrientationXMinus = 41,
01156 
01160   CF_AutomaticOrientationYPlus = 42,
01161 
01165   CF_AutomaticOrientationYMinus = 43,
01166 
01170   CF_AutomaticOrientationZPlus = 44,
01171 
01175   CF_AutomaticOrientationZMinus = 45,
01176 
01180   CF_AdvanceGOTO_1 = 46,
01181 
01185   CF_AdvanceGOTO_Clear_1 = 47,
01186 
01190   CF_AdvanceGOTO_Add_1 = 48,
01191 };
01192 
01196 struct StickEvents
01197 {
01202   unsigned char Minus;
01203 
01208   unsigned char Plus;
01209 };
01210 
01214 struct ButtonEvents
01215 {
01219   unsigned char OneClick;
01220 
01224   unsigned char TwoClick;
01225 
01229   unsigned char HoldOneSec;
01230 
01234   unsigned char HoldTwoSec;
01235 
01239   unsigned char HoldThreeSec;
01240 
01244   unsigned char HoldFourSec;
01245 
01249   unsigned char HoldDown;
01250 };
01251 
01255 enum ControlMappingMode
01256 {
01260   OneAxis,
01261 
01265   TwoAxis,
01266 
01270   ThreeAxis,
01271 
01275   SixAxis
01276 };
01277 
01282 struct ControlsModeMap
01283 {
01287   int DiagonalsLocked;
01288 
01292   int Expansion;
01293 
01297   StickEvents ControlSticks[STICK_EVENT_COUNT];
01298 
01302   ButtonEvents ControlButtons[BUTTON_EVENT_COUNT];
01303 };
01304 
01312 struct ControlMapping
01313 {
01317   int NumOfModesA;
01318 
01322   int NumOfModesB;
01323 
01328   int ActualModeA;
01329 
01334   int ActualModeB;
01335 
01339   ControlMappingMode Mode;
01340 
01345   ControlsModeMap ModeControlsA[MODE_MAP_COUNT];
01346 
01351   ControlsModeMap ModeControlsB[MODE_MAP_COUNT];
01352 };
01353 
01357 struct ControlMappingCharts
01358 {
01362   int NumOfConfiguredMapping;
01363 
01367   int ActualControlMapping;
01368 
01372   ControlMapping Mapping[CONTROL_MAPPING_COUNT];
01373 };
01374 
01378 enum errorLoggerType
01379 {
01383   ERROR_NOTINITIALIZED,
01384 
01388   keos_err1,
01389 
01393   keos_err2,
01394 
01398   keos_err3,
01399 
01403   User_err_start_marker,
01404 
01408   errorlog_Actuator_Temperature,
01409 
01413   errorlog_Actuator_TemperatureOK,
01414 
01418   errorlog_Finger_Temperature,
01419 
01423   errorlog_Finger_TemperatureOK,
01424 
01428   errorlog_voltage,
01429 
01433   errorlog_voltageOK,
01434 
01438   errorlog_current_FingersClosing,
01439 
01443   errorlog_current_FingersOpening,
01444 
01448   errorlog_current_FingersOK,
01449 
01453   errorlog_current_Actuators,
01454 
01458   errorlog_current_ActuatorsOK,
01459 
01463   errorLog_RobotStatus_Build_Incomplete,
01464 
01468   errorLogger_END
01469 };
01470 
01474 struct SystemError
01475 {
01479   unsigned int ErrorHeader;
01480 
01484   errorLoggerType ErrorType;
01485 
01489   int FirmwareVersion;
01490 
01494   int KeosVersion;
01495 
01499   unsigned int SystemTime;
01500 
01504   bool LayerErrorStatus[ERROR_LAYER_COUNT];
01505 
01509   int LifeTime;
01510 
01514   int DataCount;
01515 
01519   unsigned int Data[ERROR_DATA_COUNT_MAX];
01520 
01521 };
01522 
01526 struct ZoneLimitation
01527 {
01532   float speedParameter1;
01533 
01538   float speedParameter2;
01539 
01543   float speedParameter3;
01544 
01548   float forceParameter1;
01549 
01553   float forceParameter2;
01554 
01558   float forceParameter3;
01559 
01563   float accelerationParameter1;
01564 
01568   float accelerationParameter2;
01569 
01573   float accelerationParameter3;
01574 };
01575 
01579 enum ShapeType
01580 {
01584   PrismSquareBase_X = 0,
01585 
01589   PrismSquareBase_Y = 1,
01590 
01594   PrismSquareBase_Z = 2,
01595 
01599   PrismTriangularBase_X = 3,
01600 
01604   PrismTriangularBase_Y = 4,
01605 
01609   PrismTriangularBase_Z = 5,
01610 
01614   Pyramid = 6
01615 };
01616 
01620 struct ForcesInfo
01621 {
01625   float Actuator1;
01626 
01630   float Actuator2;
01631 
01635   float Actuator3;
01636 
01640   float Actuator4;
01641 
01645   float Actuator5;
01646 
01650   float Actuator6;
01651 
01655   float X;
01656 
01660   float Y;
01661 
01665   float Z;
01666 
01670   float ThetaX;
01671 
01675   float ThetaY;
01676 
01680   float ThetaZ;
01681 };
01682 
01686 struct QuickStatus
01687 {
01691   unsigned char Finger1Status;
01692 
01696   unsigned char Finger2Status;
01697 
01701   unsigned char Finger3Status;
01702 
01706   unsigned char RetractType;
01707 
01711   unsigned char RetractComplexity;
01712 
01716   unsigned char ControlEnableStatus;
01717 
01721   unsigned char ControlActiveModule;
01722 
01726   unsigned char ControlFrameType;
01727 
01731   unsigned char CartesianFaultState;
01732 
01736   unsigned char ForceControlStatus;
01737 
01741   unsigned char CurrentLimitationStatus;
01742 
01746   unsigned char RobotType;
01747 
01751   unsigned char RobotEdition;
01752 
01756   unsigned char TorqueSensorsStatus;
01757 };
01758 
01762 struct Finger
01763 {
01767   char ID[STRING_LENGTH];
01768 
01772   float ActualCommand;
01773 
01777   float ActualSpeed;
01778 
01782   float ActualForce;
01783 
01787   float ActualAcceleration;
01788 
01792   float ActualCurrent;
01793 
01797   float ActualPosition;
01798 
01802   float ActualAverageCurrent;
01803 
01807   float ActualTemperature;
01808 
01812   int CommunicationErrors;
01813 
01817   int OscillatorTuningValue;
01818 
01822   float CycleCount;
01823 
01827   float RunTime;
01828 
01832   float PeakMaxTemp;
01833 
01837   float PeakMinTemp;
01838 
01842   float PeakCurrent;
01843 
01847   float MaxSpeed;
01848 
01852   float MaxForce;
01853 
01857   float MaxAcceleration;
01858 
01862   float MaxCurrent;
01863 
01867   float MaxAngle;
01868 
01872   float MinAngle;
01873 
01877   unsigned int DeviceID;
01878 
01882   unsigned int CodeVersion;
01883 
01887   unsigned short IsFingerInit;
01888 
01892   unsigned short Index;
01893 
01897   unsigned short FingerAddress;
01898 
01902   unsigned short IsFingerConnected;
01903 };
01904 
01908 struct Gripper
01909 {
01913   char Model[STRING_LENGTH];
01914 
01918   Finger Fingers[JACO_FINGERS_COUNT];
01919 };
01920 
01924 struct ZoneShape
01925 {
01929   ShapeType shapeType;
01930 
01934   int Expansion1;
01935 
01939   CartesianInfo Points[LEGACY_CONFIG_NB_POINTS_COUNT];
01940 };
01941 
01945 struct Zone
01946 {
01950   int ID;
01951 
01955   int Expansion1;
01956 
01960   ZoneShape zoneShape;
01961 
01966   ZoneLimitation zoneLimitation;
01967 
01971   int Expansion2;
01972 };
01973 
01977 struct ZoneList
01978 {
01982   int NbZones;
01983 
01987   int Expansion1;
01988 
01992   Zone Zones[LEGACY_CONFIG_NB_ZONES_MAX];
01993 
01994 };
01995 
01999 struct SystemStatus
02000 {
02004   unsigned int JoystickActive;
02005 
02009   unsigned int RetractStatus;
02010 
02014   unsigned int DrinkingMode;
02015 
02019   unsigned int ArmLaterality;
02020 
02024   unsigned int TranslationActive;
02025 
02029   unsigned int RotationActive;
02030 
02034   unsigned int FingersActive;
02035 
02039   unsigned int WarningOverchargeForce;
02040 
02044   unsigned int WarningOverchargeFingers;
02045 
02049   unsigned int WarningLowVoltage;
02050 
02054   unsigned int MajorErrorOccured;
02055 };
02056 
02060 struct GeneralInformations
02061 {
02065   double TimeAbsolute;
02066 
02070   double TimeFromStartup;
02071 
02075   unsigned int IndexStartup;
02076 
02080   int ExpansionLong1;
02081 
02085   float TimeStampSavings;
02086 
02090   float ExpansionFloat;
02091 
02095   float SupplyVoltage;
02096 
02100   float TotalCurrent;
02101 
02105   float Power;
02106 
02110   float AveragePower;
02111 
02115   float AccelerationX;
02116 
02120   float AccelerationY;
02121 
02125   float AccelerationZ;
02126 
02130   float SensorExpansion1;
02131 
02135   float SensorExpansion2;
02136 
02140   float SensorExpansion3;
02141 
02145   unsigned int CodeVersion;
02146 
02150   unsigned int CodeRevision;
02151 
02155   unsigned short Status;
02156 
02160   unsigned short Controller;
02161 
02165   unsigned short ControlMode;
02166 
02170   unsigned short HandMode;
02171 
02175   unsigned short ConnectedActuatorCount;
02176 
02180   unsigned short PositionType;
02181 
02185   unsigned short ErrorsSpiExpansion1;
02186 
02190   unsigned short ErrorsSpiExpansion2;
02191 
02195   unsigned short ErrorsMainSPICount;
02196 
02200   unsigned short ErrorsExternalSPICount;
02201 
02205   unsigned short ErrorsMainCANCount;
02206 
02210   unsigned short ErrorsExternalCANCount;
02211 
02215   SystemStatus ActualSystemStatus;
02216 
02220   UserPosition Position;
02221 
02225   UserPosition Command;
02226 
02230   UserPosition Current;
02231 
02235   UserPosition Force;
02236 
02240   ZoneLimitation ActualLimitations;
02241 
02245   float ControlIncrement[6];
02246 
02250   float FingerControlIncrement[3];
02251 
02255   JoystickCommand ActualJoystickCommand;
02256 
02260   unsigned int PeripheralsConnected[4];
02261 
02265   unsigned int PeripheralsDeviceID[4];
02266 
02270   float ActuatorsTemperatures[6];
02271 
02275   float FingersTemperatures[3];
02276 
02280   float FutureTemperatures[3];
02281 
02285   int ActuatorsCommErrors[6];
02286 
02290   int FingersCommErrors[3];
02291 
02295   int ExpansionLong2;
02296 
02300   double ControlTimeAbsolute;
02301 
02306   double ControlTimeFromStartup;
02307 
02311   unsigned char ExpansionsBytes[192];
02312 };
02313 
02317 struct AngularAcceleration
02318 {
02323   float Actuator1_X;
02324 
02329   float Actuator1_Y;
02330 
02335   float Actuator1_Z;
02336 
02341   float Actuator2_X;
02342 
02347   float Actuator2_Y;
02348 
02353   float Actuator2_Z;
02354 
02359   float Actuator3_X;
02360 
02365   float Actuator3_Y;
02366 
02371   float Actuator3_Z;
02372 
02377   float Actuator4_X;
02378 
02383   float Actuator4_Y;
02384 
02389   float Actuator4_Z;
02390 
02395   float Actuator5_X;
02396 
02401   float Actuator5_Y;
02402 
02407   float Actuator5_Z;
02408 
02413   float Actuator6_X;
02414 
02419   float Actuator6_Y;
02420 
02425   float Actuator6_Z;
02426 
02430   void InitStruct()
02431   {
02432     Actuator1_X = 0.0f;
02433     Actuator1_Y = 0.0f;
02434     Actuator1_Z = 0.0f;
02435     Actuator2_X = 0.0f;
02436     Actuator2_Y = 0.0f;
02437     Actuator2_Z = 0.0f;
02438     Actuator3_X = 0.0f;
02439     Actuator3_Y = 0.0f;
02440     Actuator3_Z = 0.0f;
02441     Actuator4_X = 0.0f;
02442     Actuator4_Y = 0.0f;
02443     Actuator4_Z = 0.0f;
02444     Actuator5_X = 0.0f;
02445     Actuator5_Y = 0.0f;
02446     Actuator5_Z = 0.0f;
02447     Actuator6_X = 0.0f;
02448     Actuator6_Y = 0.0f;
02449     Actuator6_Z = 0.0f;
02450   }
02451 };
02452 
02456 struct PeripheralInfo
02457 {
02461   unsigned int Handle;
02462 
02466   unsigned int Type;
02467 
02471   unsigned int Port;
02472 
02476   unsigned int Address;
02477 
02481   unsigned int CodeVersion;
02482 };


jaco_sdk
Author(s):
autogenerated on Thu Jun 6 2019 19:43:16