Definitions.h
Go to the documentation of this file.
00001 /*************************************************************************************************************************************
00002 **                  maxon motor ag, CH-6072 Sachseln
00003 **************************************************************************************************************************************
00004 **
00005 ** FILE:            Definitions.h
00006 **
00007 ** Summary:         Functions for Linux shared library
00008 **
00009 ** Date:            10.10.2014
00010 ** Target:          x86, x86_64, arm sf/hf 
00011 ** Written by:      maxon motor ag, CH-6072 Sachseln
00012 **
00013 ** Changes:        4.8.1.0    (15.12.10): initial version
00014 **                             4.8.2.0    (14.03.11): usb interface related bugfix's
00015 **                             4.9.1.0    (27.07.12): ipm mode bugfix, kernel 2.6 support, ftdi driver update 
00016 **                             4.9.2.0    (26.04.13): rs232 baudrate bugfix, new functions: VCS_GetHomingState, VCS_WaitForHomingAttained,      **                                        VCS_GetVelocityIsAveraged, VCS_GetCurrentIsAveraged
00017 **                             5.0.1.0    (10.10.14): x86_64, arm sf/hf support, new functions: VCS_GetDriverInfo, bugfix: VCS_GetErrorInfo  
00018 *************************************************************************************************************************************/
00019 
00020 #ifndef _H_LINUX_EPOSCMD_
00021 #define _H_LINUX_EPOSCMD_
00022 
00023 //Communication
00024     int CreateCommunication();
00025     int DeleteCommunication();
00026 
00027 // INITIALISATION FUNCTIONS
00028     #define Initialisation_DllExport            extern "C"
00029     #define HelpFunctions_DllExport             extern "C"
00030 // CONFIGURATION FUNCTIONS
00031     #define Configuration_DllExport             extern "C"
00032 // OPERATION FUNCTIONS
00033     #define Status_DllExport                    extern "C"
00034     #define StateMachine_DllExport              extern "C"
00035     #define ErrorHandling_DllExport             extern "C"
00036     #define MotionInfo_DllExport                extern "C"
00037     #define ProfilePositionMode_DllExport       extern "C"
00038     #define ProfileVelocityMode_DllExport       extern "C"
00039     #define HomingMode_DllExport                extern "C"
00040     #define InterpolatedPositionMode_DllExport  extern "C"
00041     #define PositionMode_DllExport              extern "C"
00042     #define VelocityMode_DllExport              extern "C"
00043     #define CurrentMode_DllExport               extern "C"
00044     #define MasterEncoderMode_DllExport         extern "C"
00045     #define StepDirectionMode_DllExport         extern "C"
00046     #define InputsOutputs_DllExport             extern "C"
00047 // LOW LAYER FUNCTIONS
00048     #define CanLayer_DllExport                  extern "C"
00049 
00050 /*************************************************************************************************************************************
00051 * INITIALISATION FUNCTIONS
00052 *************************************************************************************************************************************/
00053 
00054 //Communication
00055     Initialisation_DllExport void*  VCS_OpenDevice(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, unsigned int* pErrorCode);
00056     Initialisation_DllExport int  VCS_SetProtocolStackSettings(void* KeyHandle, unsigned int Baudrate, unsigned int Timeout, unsigned int* pErrorCode);
00057     Initialisation_DllExport int  VCS_GetProtocolStackSettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pTimeout, unsigned int* pErrorCode);
00058     Initialisation_DllExport int  VCS_CloseDevice(void* KeyHandle, unsigned int* pErrorCode);
00059     Initialisation_DllExport int  VCS_CloseAllDevices(unsigned int* pErrorCode);
00060 
00061 //Info
00062     HelpFunctions_DllExport int  VCS_GetVersion(void* KeyHandle, unsigned short NodeId, unsigned short* pHardwareVersion, unsigned short* pSoftwareVersion, unsigned short* pApplicationNumber, unsigned short* pApplicationVersion, unsigned int* pErrorCode);
00063     HelpFunctions_DllExport int  VCS_GetErrorInfo(unsigned int ErrorCodeValue, char* pErrorInfo, unsigned short MaxStrSize);
00064     HelpFunctions_DllExport int  VCS_GetDriverInfo(char* p_pszLibraryName, unsigned short p_usMaxLibraryNameStrSize,char* p_pszLibraryVersion, unsigned short p_usMaxLibraryVersionStrSize, unsigned int* p_pErrorCode);
00065 
00066 //Advanced Functions
00067     HelpFunctions_DllExport int  VCS_GetDeviceNameSelection(int StartOfSelection, char* pDeviceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode);
00068     HelpFunctions_DllExport int  VCS_GetProtocolStackNameSelection(char* DeviceName, int StartOfSelection, char* pProtocolStackNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode);
00069     HelpFunctions_DllExport int  VCS_GetInterfaceNameSelection(char* DeviceName, char* ProtocolStackName, int StartOfSelection, char* pInterfaceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode);
00070     HelpFunctions_DllExport int  VCS_GetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, int StartOfSelection, char* pPortSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode);
00071     HelpFunctions_DllExport int  VCS_GetBaudrateSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, int StartOfSelection, unsigned int* pBaudrateSel, int* pEndOfSelection, unsigned int* pErrorCode);
00072     HelpFunctions_DllExport int  VCS_GetKeyHandle(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, void** pKeyHandle, unsigned int* pErrorCode);
00073     HelpFunctions_DllExport int  VCS_GetDeviceName(void* KeyHandle, char* pDeviceName, unsigned short MaxStrSize, unsigned int* pErrorCode);
00074     HelpFunctions_DllExport int  VCS_GetProtocolStackName(void* KeyHandle, char* pProtocolStackName, unsigned short MaxStrSize, unsigned int* pErrorCode);
00075     HelpFunctions_DllExport int  VCS_GetInterfaceName(void* KeyHandle, char* pInterfaceName, unsigned short MaxStrSize, unsigned int* pErrorCode);
00076     HelpFunctions_DllExport int  VCS_GetPortName(void* KeyHandle, char* pPortName, unsigned short MaxStrSize, unsigned int* pErrorCode);
00077 
00078 /*************************************************************************************************************************************
00079 * CONFIGURATION FUNCTIONS
00080 *************************************************************************************************************************************/
00081 
00082 //General
00083     Configuration_DllExport int  VCS_SetObject(void* KeyHandle, unsigned short NodeId, unsigned short ObjectIndex, unsigned char ObjectSubIndex, void* pData, unsigned int NbOfBytesToWrite, unsigned int* pNbOfBytesWritten, unsigned int* pErrorCode);
00084     Configuration_DllExport int  VCS_GetObject(void* KeyHandle, unsigned short NodeId, unsigned short ObjectIndex, unsigned char ObjectSubIndex, void* pData, unsigned int NbOfBytesToRead, unsigned int* pNbOfBytesRead, unsigned int* pErrorCode);
00085     Configuration_DllExport int  VCS_Restore(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00086     Configuration_DllExport int  VCS_Store(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00087 
00088 //Advanced Functions
00089     //Motor
00090     Configuration_DllExport int  VCS_SetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short MotorType, unsigned int* pErrorCode);
00091     Configuration_DllExport int  VCS_SetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short NominalCurrent, unsigned short MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode);
00092     Configuration_DllExport int  VCS_SetEcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short NominalCurrent, unsigned short MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned char NbOfPolePairs, unsigned int* pErrorCode);
00093     Configuration_DllExport int  VCS_GetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short* pMotorType, unsigned int* pErrorCode);
00094     Configuration_DllExport int  VCS_GetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pNominalCurrent, unsigned short* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode);
00095     Configuration_DllExport int  VCS_GetEcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pNominalCurrent, unsigned short* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned char* pNbOfPolePairs, unsigned int* pErrorCode);
00096 
00097     //Sensor
00098     Configuration_DllExport int  VCS_SetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short SensorType, unsigned int* pErrorCode);
00099     Configuration_DllExport int  VCS_SetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int EncoderResolution, int InvertedPolarity, unsigned int* pErrorCode);
00100     Configuration_DllExport int  VCS_SetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int InvertedPolarity, unsigned int* pErrorCode);
00101     Configuration_DllExport int  VCS_SetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, int InvertedPolarity, unsigned int* pErrorCode);
00102     Configuration_DllExport int  VCS_GetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short* pSensorType, unsigned int* pErrorCode);
00103     Configuration_DllExport int  VCS_GetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pEncoderResolution, int* pInvertedPolarity, unsigned int* pErrorCode);
00104     Configuration_DllExport int  VCS_GetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int* pInvertedPolarity, unsigned int* pErrorCode);
00105     Configuration_DllExport int  VCS_GetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, int* pInvertedPolarity, unsigned int* pErrorCode);
00106 
00107     //Safety
00108     Configuration_DllExport int  VCS_SetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int MaxFollowingError, unsigned int* pErrorCode);
00109     Configuration_DllExport int  VCS_GetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxFollowingError, unsigned int* pErrorCode);
00110     Configuration_DllExport int  VCS_SetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int MaxProfileVelocity, unsigned int* pErrorCode);
00111     Configuration_DllExport int  VCS_GetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxProfileVelocity, unsigned int* pErrorCode);
00112     Configuration_DllExport int  VCS_SetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int MaxAcceleration, unsigned int* pErrorCode);
00113     Configuration_DllExport int  VCS_GetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxAcceleration, unsigned int* pErrorCode);
00114 
00115     //Position Regulator
00116     Configuration_DllExport int  VCS_SetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned short D, unsigned int* pErrorCode);
00117     Configuration_DllExport int  VCS_SetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode);
00118     Configuration_DllExport int  VCS_GetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned short* pD, unsigned int* pErrorCode);
00119     Configuration_DllExport int  VCS_GetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode);
00120 
00121     //Velocity Regulator
00122     Configuration_DllExport int  VCS_SetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode);
00123     Configuration_DllExport int  VCS_SetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode);
00124     Configuration_DllExport int  VCS_GetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode);
00125     Configuration_DllExport int  VCS_GetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode);
00126 
00127     //Current Regulator
00128     Configuration_DllExport int  VCS_SetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode);
00129     Configuration_DllExport int  VCS_GetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode);
00130 
00131     //Inputs/Outputs
00132     Configuration_DllExport int  VCS_DigitalInputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNb, unsigned short Configuration, int Mask, int Polarity, int ExecutionMask, unsigned int* pErrorCode);
00133     Configuration_DllExport int  VCS_DigitalOutputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNb, unsigned short Configuration, int State, int Mask, int Polarity, unsigned int* pErrorCode);
00134     Configuration_DllExport int  VCS_AnalogInputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNb, unsigned short Configuration, int ExecutionMask, unsigned int* pErrorCode);
00135 
00136     //Units
00137     Configuration_DllExport int  VCS_SetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char VelDimension, signed char VelNotation, unsigned int* pErrorCode);
00138     Configuration_DllExport int  VCS_GetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char* pVelDimension, char* pVelNotation, unsigned int* pErrorCode);
00139 
00140 /*************************************************************************************************************************************
00141 * OPERATION FUNCTIONS
00142 *************************************************************************************************************************************/
00143 
00144 //OperationMode
00145     Status_DllExport int  VCS_SetOperationMode(void* KeyHandle, unsigned short NodeId, char OperationMode, unsigned int* pErrorCode);
00146     Status_DllExport int  VCS_GetOperationMode(void* KeyHandle, unsigned short NodeId, char* pOperationMode, unsigned int* pErrorCode);
00147 
00148 //StateMachine
00149     StateMachine_DllExport int  VCS_ResetDevice(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00150     StateMachine_DllExport int  VCS_SetState(void* KeyHandle, unsigned short NodeId, unsigned short State, unsigned int* pErrorCode);
00151     StateMachine_DllExport int  VCS_SetEnableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00152     StateMachine_DllExport int  VCS_SetDisableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00153     StateMachine_DllExport int  VCS_SetQuickStopState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00154     StateMachine_DllExport int  VCS_ClearFault(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00155     StateMachine_DllExport int  VCS_GetState(void* KeyHandle, unsigned short NodeId, unsigned short* pState, unsigned int* pErrorCode);
00156     StateMachine_DllExport int  VCS_GetEnableState(void* KeyHandle, unsigned short NodeId, int* pIsEnabled, unsigned int* pErrorCode);
00157     StateMachine_DllExport int  VCS_GetDisableState(void* KeyHandle, unsigned short NodeId, int* pIsDisabled, unsigned int* pErrorCode);
00158     StateMachine_DllExport int  VCS_GetQuickStopState(void* KeyHandle, unsigned short NodeId, int* pIsQuickStopped, unsigned int* pErrorCode);
00159     StateMachine_DllExport int  VCS_GetFaultState(void* KeyHandle, unsigned short NodeId, int* pIsInFault, unsigned int* pErrorCode);
00160 
00161 //ErrorHandling
00162     ErrorHandling_DllExport int  VCS_GetNbOfDeviceError(void* KeyHandle, unsigned short NodeId, unsigned char *pNbDeviceError, unsigned int *pErrorCode);
00163     ErrorHandling_DllExport int  VCS_GetDeviceErrorCode(void* KeyHandle, unsigned short NodeId, unsigned char DeviceErrorNumber, unsigned int *pDeviceErrorCode, unsigned int *pErrorCode);
00164 
00165 //Motion Info
00166     MotionInfo_DllExport int  VCS_GetMovementState(void* KeyHandle, unsigned short NodeId, int* pTargetReached, unsigned int* pErrorCode);
00167     MotionInfo_DllExport int  VCS_GetPositionIs(void* KeyHandle, unsigned short NodeId, int* pPositionIs, unsigned int* pErrorCode);
00168     MotionInfo_DllExport int  VCS_GetVelocityIs(void* KeyHandle, unsigned short NodeId, int* pVelocityIs, unsigned int* pErrorCode);
00169     MotionInfo_DllExport int  VCS_GetVelocityIsAveraged(void* KeyHandle, unsigned short NodeId, int* pVelocityIsAveraged, unsigned int* pErrorCode);
00170     MotionInfo_DllExport int  VCS_GetCurrentIs(void* KeyHandle, unsigned short NodeId, short* pCurrentIs, unsigned int* pErrorCode);
00171     MotionInfo_DllExport int  VCS_GetCurrentIsAveraged(void* KeyHandle, unsigned short NodeId, short* pCurrentIsAveraged, unsigned int* pErrorCode);
00172     MotionInfo_DllExport int  VCS_WaitForTargetReached(void* KeyHandle, unsigned short NodeId, unsigned int Timeout, unsigned int* pErrorCode);
00173 
00174 //Profile Position Mode
00175     ProfilePositionMode_DllExport int  VCS_ActivateProfilePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00176     ProfilePositionMode_DllExport int  VCS_SetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileVelocity, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode);
00177     ProfilePositionMode_DllExport int  VCS_GetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileVelocity, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode);
00178     ProfilePositionMode_DllExport int  VCS_MoveToPosition(void* KeyHandle, unsigned short NodeId, long TargetPosition, int Absolute, int Immediately, unsigned int* pErrorCode);
00179     ProfilePositionMode_DllExport int  VCS_GetTargetPosition(void* KeyHandle, unsigned short NodeId, long* pTargetPosition, unsigned int* pErrorCode);
00180     ProfilePositionMode_DllExport int  VCS_HaltPositionMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00181 
00182     //Advanced Functions
00183     ProfilePositionMode_DllExport int  VCS_EnablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int PositionWindow, unsigned short PositionWindowTime, unsigned int* pErrorCode);
00184     ProfilePositionMode_DllExport int  VCS_DisablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00185 
00186 //Profile Velocity Mode
00187     ProfileVelocityMode_DllExport int  VCS_ActivateProfileVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00188     ProfileVelocityMode_DllExport int  VCS_SetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode);
00189     ProfileVelocityMode_DllExport int  VCS_GetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode);
00190     ProfileVelocityMode_DllExport int  VCS_MoveWithVelocity(void* KeyHandle, unsigned short NodeId, long TargetVelocity, unsigned int* pErrorCode);
00191     ProfileVelocityMode_DllExport int  VCS_GetTargetVelocity(void* KeyHandle, unsigned short NodeId, long* pTargetVelocity, unsigned int* pErrorCode);
00192     ProfileVelocityMode_DllExport int  VCS_HaltVelocityMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00193 
00194     //Advanced Functions
00195     ProfileVelocityMode_DllExport int  VCS_EnableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int VelocityWindow, unsigned short VelocityWindowTime, unsigned int* pErrorCode);
00196     ProfileVelocityMode_DllExport int  VCS_DisableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00197 
00198 //Homing Mode
00199     HomingMode_DllExport int  VCS_ActivateHomingMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00200     HomingMode_DllExport int  VCS_SetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int HomingAcceleration, unsigned int SpeedSwitch, unsigned int SpeedIndex, int HomeOffset, unsigned short CurrentTreshold, int HomePosition, unsigned int* pErrorCode);
00201     HomingMode_DllExport int  VCS_GetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pHomingAcceleration, unsigned int* pSpeedSwitch, unsigned int* pSpeedIndex, int* pHomeOffset, unsigned short* pCurrentTreshold, int* pHomePosition, unsigned int* pErrorCode);
00202     HomingMode_DllExport int  VCS_FindHome(void* KeyHandle, unsigned short NodeId, signed char HomingMethod, unsigned int* pErrorCode);
00203     HomingMode_DllExport int  VCS_StopHoming(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00204     HomingMode_DllExport int  VCS_DefinePosition(void* KeyHandle, unsigned short NodeId, int HomePosition, unsigned int* pErrorCode);
00205     HomingMode_DllExport int  VCS_WaitForHomingAttained(void* KeyHandle, unsigned short NodeId, int Timeout, unsigned int* pErrorCode);
00206     HomingMode_DllExport int  VCS_GetHomingState(void* KeyHandle, unsigned short NodeId, int* pHomingAttained, int* pHomingError, unsigned int* pErrorCode);
00207 
00208 //Interpolated Position Mode
00209     InterpolatedPositionMode_DllExport int  VCS_ActivateInterpolatedPositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00210     InterpolatedPositionMode_DllExport int  VCS_SetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short UnderflowWarningLimit, unsigned short OverflowWarningLimit, unsigned int* pErrorCode);
00211     InterpolatedPositionMode_DllExport int  VCS_GetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pUnderflowWarningLimit, unsigned short* pOverflowWarningLimit, unsigned int* pMaxBufferSize, unsigned int* pErrorCode);
00212     InterpolatedPositionMode_DllExport int  VCS_ClearIpmBuffer(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00213     InterpolatedPositionMode_DllExport int  VCS_GetFreeIpmBufferSize(void* KeyHandle, unsigned short NodeId, unsigned int* pBufferSize, unsigned int* pErrorCode);
00214     InterpolatedPositionMode_DllExport int  VCS_AddPvtValueToIpmBuffer(void* KeyHandle, unsigned short NodeId, long Position, long Velocity, unsigned char Time, unsigned int* pErrorCode);
00215     InterpolatedPositionMode_DllExport int  VCS_StartIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00216     InterpolatedPositionMode_DllExport int  VCS_StopIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00217     InterpolatedPositionMode_DllExport int  VCS_GetIpmStatus(void* KeyHandle, unsigned short NodeId, int* pTrajectoryRunning, int* pIsUnderflowWarning, int* pIsOverflowWarning, int* pIsVelocityWarning, int* pIsAccelerationWarning, int* pIsUnderflowError, int* pIsOverflowError, int* pIsVelocityError, int* pIsAccelerationError, unsigned int* pErrorCode);
00218 
00219 //Position Mode
00220     PositionMode_DllExport int  VCS_ActivatePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00221     PositionMode_DllExport int  VCS_SetPositionMust(void* KeyHandle, unsigned short NodeId, long PositionMust, unsigned int* pErrorCode);
00222     PositionMode_DllExport int  VCS_GetPositionMust(void* KeyHandle, unsigned short NodeId, long* pPositionMust, unsigned int* pErrorCode);
00223 
00224     //Advanced Functions
00225     PositionMode_DllExport int  VCS_ActivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode);
00226     PositionMode_DllExport int  VCS_DeactivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode);
00227     PositionMode_DllExport int  VCS_EnableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00228     PositionMode_DllExport int  VCS_DisableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00229 
00230 //Velocity Mode
00231     VelocityMode_DllExport int  VCS_ActivateVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00232     VelocityMode_DllExport int  VCS_SetVelocityMust(void* KeyHandle, unsigned short NodeId, long VelocityMust, unsigned int* pErrorCode);
00233     VelocityMode_DllExport int  VCS_GetVelocityMust(void* KeyHandle, unsigned short NodeId, long* pVelocityMust, unsigned int* pErrorCode);
00234 
00235     //Advanced Functions
00236     VelocityMode_DllExport int  VCS_ActivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode);
00237     VelocityMode_DllExport int  VCS_DeactivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode);
00238     VelocityMode_DllExport int  VCS_EnableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00239     VelocityMode_DllExport int  VCS_DisableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00240 
00241 //Current Mode
00242     CurrentMode_DllExport int  VCS_ActivateCurrentMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00243     CurrentMode_DllExport int  VCS_SetCurrentMust(void* KeyHandle, unsigned short NodeId, short CurrentMust, unsigned int* pErrorCode);
00244     CurrentMode_DllExport int  VCS_GetCurrentMust(void* KeyHandle, unsigned short NodeId, short* pCurrentMust, unsigned int* pErrorCode);
00245 
00246     //Advanced Functions
00247     CurrentMode_DllExport int  VCS_ActivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, short Offset, unsigned int* pErrorCode);
00248     CurrentMode_DllExport int  VCS_DeactivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode);
00249     CurrentMode_DllExport int  VCS_EnableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00250     CurrentMode_DllExport int  VCS_DisableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00251 
00252 //MasterEncoder Mode
00253     MasterEncoderMode_DllExport int  VCS_ActivateMasterEncoderMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00254     MasterEncoderMode_DllExport int  VCS_SetMasterEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short ScalingNumerator, unsigned short ScalingDenominator, unsigned char Polarity, unsigned int MaxVelocity, unsigned int MaxAcceleration, unsigned int* pErrorCode);
00255     MasterEncoderMode_DllExport int  VCS_GetMasterEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pScalingNumerator, unsigned short* pScalingDenominator, unsigned char* pPolarity, unsigned int* pMaxVelocity, unsigned int* pMaxAcceleration, unsigned int* pErrorCode);
00256 
00257 //StepDirection Mode
00258     StepDirectionMode_DllExport int  VCS_ActivateStepDirectionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00259     StepDirectionMode_DllExport int  VCS_SetStepDirectionParameter(void* KeyHandle, unsigned short NodeId, unsigned short ScalingNumerator, unsigned short ScalingDenominator, unsigned char Polarity, unsigned int MaxVelocity, unsigned int MaxAcceleration, unsigned int* pErrorCode);
00260     StepDirectionMode_DllExport int  VCS_GetStepDirectionParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pScalingNumerator, unsigned short* pScalingDenominator, unsigned char* pPolarity, unsigned int* pMaxVelocity, unsigned int* pMaxAcceleration, unsigned int* pErrorCode);
00261 
00262 //Inputs Outputs
00263     //General
00264     InputsOutputs_DllExport int  VCS_GetAllDigitalInputs(void* KeyHandle, unsigned short NodeId, unsigned short* pInputs, unsigned int* pErrorCode);
00265     InputsOutputs_DllExport int  VCS_GetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short* pOutputs, unsigned int* pErrorCode);
00266     InputsOutputs_DllExport int  VCS_SetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short Outputs, unsigned int* pErrorCode);
00267     InputsOutputs_DllExport int  VCS_GetAnalogInput(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, unsigned short* pAnalogValue, unsigned int* pErrorCode);
00268     InputsOutputs_DllExport int  VCS_SetAnalogOutput(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, unsigned short AnalogValue, unsigned int* pErrorCode);
00269 
00270     //Position Compare
00271     InputsOutputs_DllExport int  VCS_SetPositionCompareParameter(void* KeyHandle, unsigned short NodeId, unsigned char OperationalMode, unsigned char IntervalMode, unsigned char DirectionDependency, unsigned short IntervalWidth, unsigned short IntervalRepetitions, unsigned short PulseWidth, unsigned int* pErrorCode);
00272     InputsOutputs_DllExport int  VCS_GetPositionCompareParameter(void* KeyHandle, unsigned short NodeId, unsigned char* pOperationalMode, unsigned char* pIntervalMode, unsigned char* pDirectionDependency, unsigned short* pIntervalWidth, unsigned short* pIntervalRepetitions, unsigned short* pPulseWidth, unsigned int* pErrorCode);
00273     InputsOutputs_DllExport int  VCS_ActivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, int Polarity, unsigned int* pErrorCode);
00274     InputsOutputs_DllExport int  VCS_DeactivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, unsigned int* pErrorCode);
00275     InputsOutputs_DllExport int  VCS_EnablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00276     InputsOutputs_DllExport int  VCS_DisablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00277     InputsOutputs_DllExport int  VCS_SetPositionCompareReferencePosition(void* KeyHandle, unsigned short NodeId, long ReferencePosition, unsigned int* pErrorCode);
00278 
00279     //Position Marker
00280     InputsOutputs_DllExport int  VCS_SetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char PositionMarkerEdgeType, unsigned char PositionMarkerMode, unsigned int* pErrorCode);
00281     InputsOutputs_DllExport int  VCS_GetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char* pPositionMarkerEdgeType, unsigned char* pPositionMarkerMode, unsigned int* pErrorCode);
00282     InputsOutputs_DllExport int  VCS_ActivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, int Polarity, unsigned int* pErrorCode);
00283     InputsOutputs_DllExport int  VCS_DeactivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, unsigned int* pErrorCode);
00284     InputsOutputs_DllExport int  VCS_ReadPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned short* pCount, unsigned int* pErrorCode);
00285     InputsOutputs_DllExport int  VCS_ReadPositionMarkerCapturedPosition(void* KeyHandle, unsigned short NodeId, unsigned short CounterIndex, long* pCapturedPosition, unsigned int* pErrorCode);
00286     InputsOutputs_DllExport int  VCS_ResetPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode);
00287 
00288 /*************************************************************************************************************************************
00289 * LOW LAYER FUNCTIONS
00290 *************************************************************************************************************************************/
00291 
00292 //CanLayer Functions
00293     CanLayer_DllExport int  VCS_SendCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode);
00294     CanLayer_DllExport int  VCS_ReadCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int Timeout, unsigned int* pErrorCode);
00295     CanLayer_DllExport int  VCS_RequestCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode);
00296     CanLayer_DllExport int  VCS_SendNMTService(void* KeyHandle, unsigned short NodeId, unsigned short CommandSpecifier, unsigned int* pErrorCode);
00297 
00298 /*************************************************************************************************************************************
00299 * TYPE DEFINITIONS
00300 *************************************************************************************************************************************/
00301 //Communication
00302         //Dialog Mode
00303         const int DM_PROGRESS_DLG                                       = 0;
00304         const int DM_PROGRESS_AND_CONFIRM_DLG           = 1;
00305         const int DM_CONFIRM_DLG                                        = 2;
00306         const int DM_NO_DLG                                                     = 3;
00307 
00308 //Configuration
00309     //MotorType
00310     const unsigned short MT_DC_MOTOR                      = 1;
00311     const unsigned short MT_EC_SINUS_COMMUTATED_MOTOR     = 10;
00312     const unsigned short MT_EC_BLOCK_COMMUTATED_MOTOR     = 11;
00313 
00314     //SensorType
00315     const unsigned short ST_UNKNOWN                       = 0;
00316     const unsigned short ST_INC_ENCODER_3CHANNEL          = 1;
00317     const unsigned short ST_INC_ENCODER_2CHANNEL          = 2;
00318     const unsigned short ST_HALL_SENSORS                  = 3;
00319     const unsigned short ST_SSI_ABS_ENCODER_BINARY        = 4;
00320     const unsigned short ST_SSI_ABS_ENCODER_GREY          = 5;
00321 
00322 //In- and outputs
00323     //Digital input configuration
00324     const unsigned short DIC_NEGATIVE_LIMIT_SWITCH        = 0;
00325     const unsigned short DIC_POSITIVE_LIMIT_SWITCH        = 1;
00326     const unsigned short DIC_HOME_SWITCH                  = 2;
00327     const unsigned short DIC_POSITION_MARKER              = 3;
00328     const unsigned short DIC_DRIVE_ENABLE                 = 4;
00329     const unsigned short DIC_QUICK_STOP                   = 5;
00330     const unsigned short DIC_GENERAL_PURPOSE_J            = 6;
00331     const unsigned short DIC_GENERAL_PURPOSE_I            = 7;
00332     const unsigned short DIC_GENERAL_PURPOSE_H            = 8;
00333     const unsigned short DIC_GENERAL_PURPOSE_G            = 9;
00334     const unsigned short DIC_GENERAL_PURPOSE_F            = 10;
00335     const unsigned short DIC_GENERAL_PURPOSE_E            = 11;
00336     const unsigned short DIC_GENERAL_PURPOSE_D            = 12;
00337     const unsigned short DIC_GENERAL_PURPOSE_C            = 13;
00338     const unsigned short DIC_GENERAL_PURPOSE_B            = 14;
00339     const unsigned short DIC_GENERAL_PURPOSE_A            = 15;
00340 
00341     //Digital output configuration
00342     const unsigned short DOC_READY_FAULT                  = 0;
00343     const unsigned short DOC_POSITION_COMPARE             = 1;
00344     const unsigned short DOC_GENERAL_PURPOSE_H            = 8;
00345     const unsigned short DOC_GENERAL_PURPOSE_G            = 9;
00346     const unsigned short DOC_GENERAL_PURPOSE_F            = 10;
00347     const unsigned short DOC_GENERAL_PURPOSE_E            = 11;
00348     const unsigned short DOC_GENERAL_PURPOSE_D            = 12;
00349     const unsigned short DOC_GENERAL_PURPOSE_C            = 13;
00350     const unsigned short DOC_GENERAL_PURPOSE_B            = 14;
00351     const unsigned short DOC_GENERAL_PURPOSE_A            = 15;
00352 
00353     //Analog input configuration
00354     const unsigned short AIC_ANALOG_CURRENT_SETPOINT      = 0;
00355     const unsigned short AIC_ANALOG_VELOCITY_SETPOINT     = 1;
00356     const unsigned short AIC_ANALOG_POSITION_SETPOINT     = 2;
00357 
00358 //Units
00359     //VelocityDimension
00360     const unsigned char VD_RPM                               = 0xA4;
00361 
00362     //VelocityNotation
00363     const signed char VN_STANDARD                          = 0;
00364     const signed char VN_DECI                              = -1;
00365     const signed char VN_CENTI                             = -2;
00366     const signed char VN_MILLI                             = -3;
00367 
00368 //Operational mode 
00369     const signed char OMD_PROFILE_POSITION_MODE          = 1;
00370     const signed char OMD_PROFILE_VELOCITY_MODE          = 3;
00371     const signed char OMD_HOMING_MODE                    = 6;
00372     const signed char OMD_INTERPOLATED_POSITION_MODE     = 7;
00373     const signed char OMD_POSITION_MODE                  = -1;
00374     const signed char OMD_VELOCITY_MODE                  = -2;
00375     const signed char OMD_CURRENT_MODE                   = -3;
00376     const signed char OMD_MASTER_ENCODER_MODE            = -5;
00377     const signed char OMD_STEP_DIRECTION_MODE            = -6;
00378 
00379 //States
00380     const unsigned short ST_DISABLED                         = 0;
00381     const unsigned short ST_ENABLED                          = 1;
00382     const unsigned short ST_QUICKSTOP                        = 2;
00383     const unsigned short ST_FAULT                            = 3;
00384 
00385 //Homing mode
00386     //Homing method
00387     const char HM_ACTUAL_POSITION                               = 35;
00388     const char HM_NEGATIVE_LIMIT_SWITCH                         = 17;
00389     const char HM_NEGATIVE_LIMIT_SWITCH_AND_INDEX               = 1;
00390     const char HM_POSITIVE_LIMIT_SWITCH                         = 18;
00391     const char HM_POSITIVE_LIMIT_SWITCH_AND_INDEX               = 2;
00392     const char HM_HOME_SWITCH_POSITIVE_SPEED                    = 23;
00393     const char HM_HOME_SWITCH_POSITIVE_SPEED_AND_INDEX          = 7;
00394     const char HM_HOME_SWITCH_NEGATIVE_SPEED                    = 27;
00395     const char HM_HOME_SWITCH_NEGATIVE_SPEED_AND_INDEX          = 11;
00396     const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED              = -3;
00397     const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED_AND_INDEX    = -1;
00398     const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED              = -4;
00399     const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED_AND_INDEX    = -2;
00400     const char HM_INDEX_POSITIVE_SPEED                          = 34;
00401     const char HM_INDEX_NEGATIVE_SPEED                          = 33;
00402 
00403 //Input Output PositionMarker
00404     //PositionMarkerEdgeType
00405     const unsigned char PET_BOTH_EDGES                   = 0;
00406     const unsigned char PET_RISING_EDGE                  = 1;
00407     const unsigned char PET_FALLING_EDGE                 = 2;
00408 
00409     //PositionMarkerMode
00410     const unsigned char PM_CONTINUOUS                    = 0;
00411     const unsigned char PM_SINGLE                        = 1;
00412     const unsigned char PM_MULTIPLE                      = 2;
00413 
00414 //Input Output PositionCompare
00415     //PositionCompareOperationalMode
00416     const unsigned char PCO_SINGLE_POSITION_MODE         = 0;
00417     const unsigned char PCO_POSITION_SEQUENCE_MODE       = 1;
00418 
00419     //PositionCompareIntervalMode
00420     const unsigned char PCI_NEGATIVE_DIR_TO_REFPOS       = 0;
00421     const unsigned char PCI_POSITIVE_DIR_TO_REFPOS       = 1;
00422     const unsigned char PCI_BOTH_DIR_TO_REFPOS           = 2;
00423 
00424     //PositionCompareDirectionDependency
00425     const unsigned char PCD_MOTOR_DIRECTION_NEGATIVE     = 0;
00426     const unsigned char PCD_MOTOR_DIRECTION_POSITIVE     = 1;
00427     const unsigned char PCD_MOTOR_DIRECTION_BOTH         = 2;
00428 
00429 //Data recorder
00430     //Trigger type
00431     const unsigned short DR_MOVEMENT_START_TRIGGER        = 1;    //bit 1
00432     const unsigned short DR_ERROR_TRIGGER                 = 2;    //bit 2
00433     const unsigned short DR_DIGITAL_INPUT_TRIGGER         = 4;    //bit 3
00434     const unsigned short DR_MOVEMENT_END_TRIGGER          = 8;    //bit 4
00435 
00436 //CanLayer Functions
00437     const unsigned short NCS_START_REMOTE_NODE            = 1;
00438     const unsigned short NCS_STOP_REMOTE_NODE             = 2;
00439     const unsigned short NCS_ENTER_PRE_OPERATIONAL        = 128;
00440     const unsigned short NCS_RESET_NODE                   = 129;
00441     const unsigned short NCS_RESET_COMMUNICATION          = 130;
00442 
00443 #endif //_H_LINUX_EPOSCMD_
00444 
00445 


epos_library
Author(s):
autogenerated on Thu Jun 6 2019 20:43:08