From 55639a3859027a36f8e23f4094f6cffc49e3a61e Mon Sep 17 00:00:00 2001 From: JC Luna Date: Tue, 10 Mar 2026 16:00:35 -0500 Subject: [PATCH 01/37] Emphasize that Maxon owns these components --- epos2/LICENSE | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 epos2/LICENSE diff --git a/epos2/LICENSE b/epos2/LICENSE new file mode 100644 index 0000000..0994412 --- /dev/null +++ b/epos2/LICENSE @@ -0,0 +1,3 @@ +The EPOS brand of controllers and associated command library is copyright © maxon. All rights reserved. + +No infringement or intent thereof is made by the developers of this software. From 7ee5614759b73fd82d20f6ec844a7df6fd430afe Mon Sep 17 00:00:00 2001 From: JC Luna Date: Tue, 10 Mar 2026 18:59:54 -0500 Subject: [PATCH 02/37] Nested epos meson.build for grabbing it as a dependency --- .gitignore | 5 +++++ epos2/meson.build | 24 ++++++++++++++++++++++++ meson.build | 11 ++++++++++- 3 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 epos2/meson.build diff --git a/.gitignore b/.gitignore index 260a04a..72e7ff1 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,8 @@ build compile_commands.json .cache .meson-subproject-wrap-hash.txt + +*.a* +*.so* +*.lib +*.dll diff --git a/epos2/meson.build b/epos2/meson.build new file mode 100644 index 0000000..567e757 --- /dev/null +++ b/epos2/meson.build @@ -0,0 +1,24 @@ +cc = meson.get_compiler('c') + +# Windows +if (operating_system == 'windows') + if not (cpu_architecture in ['x86', 'x86_64']) + error('Unsupported architecture') + endif + +# Linux +elif (operating_system == 'linux') + if not (cpu_architecture in valid_arch) + error('Unsupported architecture') + endif + + epos2 = declare_dependency( + dependencies: cc.find_library('EposCmd', + dirs: [meson.current_source_dir() / 'bin'], + required: false)) + #FIXME this is for CI + +# Others +else + error('Unsupported operating system') +endif diff --git a/meson.build b/meson.build index a7be4f9..fff2f74 100644 --- a/meson.build +++ b/meson.build @@ -1,7 +1,16 @@ project('libtestrig', 'c') +## Machine info +operating_system = host_machine.system() +cpu_architecture = host_machine.cpu_family() +valid_os = ['windows', 'linux'] +valid_arch = ['x86', 'x86_64', 'aarch64', 'arm'] + +## Main Binary Definitions +subdir('epos2') srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c' ] lib = shared_library('testrig', srcs) -dep = declare_dependency(include_directories: '.', link_with: lib) +dep = declare_dependency(include_directories: '.', + link_with: lib, dependencies: epos2) subdir('test') From 70290a4c9e6109a16a800afb56f97ea5ffb73d7f Mon Sep 17 00:00:00 2001 From: JC Luna Date: Tue, 10 Mar 2026 20:01:04 -0500 Subject: [PATCH 03/37] Acquire device info --- epos2/constants.c | 1 + epos2/constants.h | 23 +++++++++++++++++++++++ epos2/ident.c | 26 ++++++++++++++++++++++++++ epos2/ident.h | 25 +++++++++++++++++++++++++ epos2/meson.build | 2 ++ ipc/constants.h | 4 ++-- 6 files changed, 79 insertions(+), 2 deletions(-) create mode 100644 epos2/constants.c create mode 100644 epos2/constants.h create mode 100644 epos2/ident.c create mode 100644 epos2/ident.h diff --git a/epos2/constants.c b/epos2/constants.c new file mode 100644 index 0000000..04a2aa6 --- /dev/null +++ b/epos2/constants.c @@ -0,0 +1 @@ +#include "constants.h" diff --git a/epos2/constants.h b/epos2/constants.h new file mode 100644 index 0000000..2aceaeb --- /dev/null +++ b/epos2/constants.h @@ -0,0 +1,23 @@ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#ifdef __cplusplus +} +namespace VSCL::Rig { +extern "C" { +#endif // __cplusplus + +enum ACQUIRE_DEVICE_INFORMATION_FLAGS { + FLAG_INIT_DEFAULTS = 1, + FLAG_ZERO_INIT = 2 +}; + +#ifdef __cplusplus +} // extern "C" +} // namespace VSCL::Rig +#endif // __cplusplus diff --git a/epos2/ident.c b/epos2/ident.c new file mode 100644 index 0000000..4a98efa --- /dev/null +++ b/epos2/ident.c @@ -0,0 +1,26 @@ +#include +#include + +#include "definitions.h" +#include "ident.h" + +int AcquireDeviceInformation(struct Controller* controller, int flags) { + unsigned int error_code = 0; + int success; + int selection_end; + + if (flags & (1 << 2)) { memset(controller, 0, sizeof(*controller)); } + + if (flags & (1 << 1)) { + strncpy(controller->Name, "EPOS2", 6); + strncpy(controller->Protocol, "CANopen", 6); + } + + // TODO: will this behave expectedly? + // i.e only one connection to host pc means only one controller shows up? + // or all three will show + success = VCS_GetInterfaceNameSelection(controller->Name, controller->Protocol, 1, + controller->Interface, 64, &selection_end, &error_code); + + return error_code; +} diff --git a/epos2/ident.h b/epos2/ident.h new file mode 100644 index 0000000..8f11a7d --- /dev/null +++ b/epos2/ident.h @@ -0,0 +1,25 @@ +#pragma once + +#ifdef __cplusplus +namespace VSCL::Rig { +extern "C" { +#endif // __cplusplus + +struct Controller { + char Name[8]; + char Protocol[16]; + char Interface[64]; + char Port[8]; +}; + +/* + * Populates the fields of the Controller information struct. + * + * Flags are passed bitwise ORed. + */ +int AcquireDeviceInformation(struct Controller* controller, int flags); + +#ifdef __cplusplus +} // extern "C" +} // namespace VSCL::Rig +#endif // __cplusplus diff --git a/epos2/meson.build b/epos2/meson.build index 567e757..1b41594 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -1,5 +1,7 @@ cc = meson.get_compiler('c') +epos2_srcs = [ './constants.c', './ident.c' ] + # Windows if (operating_system == 'windows') if not (cpu_architecture in ['x86', 'x86_64']) diff --git a/ipc/constants.h b/ipc/constants.h index e981f2a..79b7109 100644 --- a/ipc/constants.h +++ b/ipc/constants.h @@ -8,7 +8,7 @@ extern "C" { #ifdef __cplusplus } -namespace VSCL { +namespace VSCL::IPC { extern "C" { #endif // __cplusplus @@ -50,5 +50,5 @@ enum HEADER_RET { #ifdef __cplusplus } // extern "C" -} // namespace VSCL +} // namespace VSCL::IPC #endif // __cplusplus From ee6b5adf8c929eebbdb097a41900c66e9acd928e Mon Sep 17 00:00:00 2001 From: JC Luna Date: Tue, 10 Mar 2026 20:06:41 -0500 Subject: [PATCH 04/37] Actually to EPOS2 libraries (if they're there) --- epos2/meson.build | 4 +++- meson.build | 4 ++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/epos2/meson.build b/epos2/meson.build index 1b41594..85c4ad0 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -1,6 +1,6 @@ cc = meson.get_compiler('c') -epos2_srcs = [ './constants.c', './ident.c' ] +epos2_srcs = [ ] # Windows if (operating_system == 'windows') @@ -20,6 +20,8 @@ elif (operating_system == 'linux') required: false)) #FIXME this is for CI + epos2_srcs += [ './epos2/constants.c', './epos2/ident.c' ] + # Others else error('Unsupported operating system') diff --git a/meson.build b/meson.build index fff2f74..bb6c6f3 100644 --- a/meson.build +++ b/meson.build @@ -8,8 +8,8 @@ valid_arch = ['x86', 'x86_64', 'aarch64', 'arm'] ## Main Binary Definitions subdir('epos2') -srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c' ] -lib = shared_library('testrig', srcs) +srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c' ] + epos2_srcs +lib = shared_library('testrig', srcs, dependencies: epos2) dep = declare_dependency(include_directories: '.', link_with: lib, dependencies: epos2) From 9d6caffbbe5acda8c12fe60f2ac1dfc935974c84 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Tue, 10 Mar 2026 20:11:55 -0500 Subject: [PATCH 05/37] Don't add controller interface sources if you can't --- epos2/ident.c | 4 ++-- epos2/meson.build | 15 ++++++++++----- meson.build | 4 +++- 3 files changed, 15 insertions(+), 8 deletions(-) diff --git a/epos2/ident.c b/epos2/ident.c index 4a98efa..8430b73 100644 --- a/epos2/ident.c +++ b/epos2/ident.c @@ -13,7 +13,7 @@ int AcquireDeviceInformation(struct Controller* controller, int flags) { if (flags & (1 << 1)) { strncpy(controller->Name, "EPOS2", 6); - strncpy(controller->Protocol, "CANopen", 6); + strncpy(controller->Protocol, "CANopen", 8); } // TODO: will this behave expectedly? @@ -22,5 +22,5 @@ int AcquireDeviceInformation(struct Controller* controller, int flags) { success = VCS_GetInterfaceNameSelection(controller->Name, controller->Protocol, 1, controller->Interface, 64, &selection_end, &error_code); - return error_code; + return (success == 0) ? 0 : error_code; } diff --git a/epos2/meson.build b/epos2/meson.build index 85c4ad0..f8e6efa 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -1,7 +1,5 @@ cc = meson.get_compiler('c') -epos2_srcs = [ ] - # Windows if (operating_system == 'windows') if not (cpu_architecture in ['x86', 'x86_64']) @@ -17,10 +15,17 @@ elif (operating_system == 'linux') epos2 = declare_dependency( dependencies: cc.find_library('EposCmd', dirs: [meson.current_source_dir() / 'bin'], - required: false)) - #FIXME this is for CI + required: false), + version: '6.8.1.0' + ) - epos2_srcs += [ './epos2/constants.c', './epos2/ident.c' ] + if (epos2.found()) + message('Controller capabilities being built.') + epos2_srcs = [ './epos2/constants.c', './epos2/ident.c' ] + else + message('[WARNING] Controller capabilities not being built. Continuing to create library anyway') + epos2_srcs = [ ] + endif # Others else diff --git a/meson.build b/meson.build index bb6c6f3..135315e 100644 --- a/meson.build +++ b/meson.build @@ -8,8 +8,10 @@ valid_arch = ['x86', 'x86_64', 'aarch64', 'arm'] ## Main Binary Definitions subdir('epos2') +# hack? +actually_epos = epos2.found() ? epos2 : declare_dependency() srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c' ] + epos2_srcs -lib = shared_library('testrig', srcs, dependencies: epos2) +lib = shared_library('testrig', srcs, dependencies: actually_epos ) dep = declare_dependency(include_directories: '.', link_with: lib, dependencies: epos2) From 352f88dc6b009e66523866c05f355f88e6e7714c Mon Sep 17 00:00:00 2001 From: JC Luna Date: Tue, 10 Mar 2026 20:33:03 -0500 Subject: [PATCH 06/37] an actually proper guard for CI only --- epos2/meson.build | 14 +++++++++++--- meson.build | 3 +-- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/epos2/meson.build b/epos2/meson.build index f8e6efa..3adced2 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -1,5 +1,7 @@ +fs = import('fs') cc = meson.get_compiler('c') +if (fs.is_dir(meson.current_source_dir() / 'bin')) # Windows if (operating_system == 'windows') if not (cpu_architecture in ['x86', 'x86_64']) @@ -13,10 +15,10 @@ elif (operating_system == 'linux') endif epos2 = declare_dependency( - dependencies: cc.find_library('EposCmd', - dirs: [meson.current_source_dir() / 'bin'], - required: false), version: '6.8.1.0' + dependencies: cc.find_library('EposCmd', + dirs: [meson.current_source_dir() / 'bin'], + required: false), ) if (epos2.found()) @@ -31,3 +33,9 @@ elif (operating_system == 'linux') else error('Unsupported operating system') endif + +# CI etc. +else +epos2 = declare_dependency() +epos2_srcs = [ ] +endif diff --git a/meson.build b/meson.build index 135315e..b70e8d6 100644 --- a/meson.build +++ b/meson.build @@ -9,9 +9,8 @@ valid_arch = ['x86', 'x86_64', 'aarch64', 'arm'] ## Main Binary Definitions subdir('epos2') # hack? -actually_epos = epos2.found() ? epos2 : declare_dependency() srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c' ] + epos2_srcs -lib = shared_library('testrig', srcs, dependencies: actually_epos ) +lib = shared_library('testrig', srcs, dependencies: epos2 ) dep = declare_dependency(include_directories: '.', link_with: lib, dependencies: epos2) From 7afd5644aa3a8607ada5d0a9a82234085a0b789d Mon Sep 17 00:00:00 2001 From: JC Luna Date: Tue, 10 Mar 2026 20:34:51 -0500 Subject: [PATCH 07/37] Don't forget the comma --- epos2/meson.build | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/epos2/meson.build b/epos2/meson.build index 3adced2..7f84116 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -2,6 +2,9 @@ fs = import('fs') cc = meson.get_compiler('c') if (fs.is_dir(meson.current_source_dir() / 'bin')) + +message('Controller capabilities being built.') + # Windows if (operating_system == 'windows') if not (cpu_architecture in ['x86', 'x86_64']) @@ -15,19 +18,13 @@ elif (operating_system == 'linux') endif epos2 = declare_dependency( - version: '6.8.1.0' + version: '6.8.1.0', dependencies: cc.find_library('EposCmd', dirs: [meson.current_source_dir() / 'bin'], required: false), ) - if (epos2.found()) - message('Controller capabilities being built.') - epos2_srcs = [ './epos2/constants.c', './epos2/ident.c' ] - else - message('[WARNING] Controller capabilities not being built. Continuing to create library anyway') - epos2_srcs = [ ] - endif + epos2_srcs = [ './epos2/constants.c', './epos2/ident.c' ] # Others else @@ -36,6 +33,7 @@ endif # CI etc. else -epos2 = declare_dependency() -epos2_srcs = [ ] + message('[WARNING] Controller capabilities not being built. Continuing to create library anyway') + epos2 = declare_dependency() + epos2_srcs = [ ] endif From 3d55ef6d89596aa2f0312165bde468853f8bd8dd Mon Sep 17 00:00:00 2001 From: JC Luna Date: Sun, 15 Mar 2026 21:33:36 -0500 Subject: [PATCH 08/37] dll export --- epos2/definitions.h | 886 +++++++++++++++++++++++--------------------- 1 file changed, 469 insertions(+), 417 deletions(-) diff --git a/epos2/definitions.h b/epos2/definitions.h index 6b47795..c49704a 100644 --- a/epos2/definitions.h +++ b/epos2/definitions.h @@ -1,5 +1,57 @@ +// ******************************************************************************************************************* +// maxon motor ag, CH-6072 Sachseln +// ******************************************************************************************************************* +// Copyright © 2003 - 2021, maxon motor ag. +// All rights reserved. +// ******************************************************************************************************************* + #pragma once +#ifndef EposDllExports +#define EposDllExports +#if defined(_WIN32) && !defined(__GNUC__) + #define Initialisation_DllExport __declspec(dllexport) + #define HelpFunctions_DllExport __declspec(dllexport) + #define Configuration_DllExport __declspec(dllexport) + #define Status_DllExport __declspec(dllexport) + #define StateMachine_DllExport __declspec(dllexport) + #define ErrorHandling_DllExport __declspec(dllexport) + #define MotionInfo_DllExport __declspec(dllexport) + #define ProfilePositionMode_DllExport __declspec(dllexport) + #define ProfileVelocityMode_DllExport __declspec(dllexport) + #define HomingMode_DllExport __declspec(dllexport) + #define InterpolatedPositionMode_DllExport __declspec(dllexport) + #define PositionMode_DllExport __declspec(dllexport) + #define VelocityMode_DllExport __declspec(dllexport) + #define CurrentMode_DllExport __declspec(dllexport) + #define MasterEncoderMode_DllExport __declspec(dllexport) + #define StepDirectionMode_DllExport __declspec(dllexport) + #define InputsOutputs_DllExport __declspec(dllexport) + #define DataRecording_DllExport __declspec(dllexport) + #define CanLayer_DllExport __declspec(dllexport) +#else + #define Initialisation_DllExport + #define HelpFunctions_DllExport + #define Configuration_DllExport + #define Status_DllExport + #define StateMachine_DllExport + #define ErrorHandling_DllExport + #define MotionInfo_DllExport + #define ProfilePositionMode_DllExport + #define ProfileVelocityMode_DllExport + #define HomingMode_DllExport + #define InterpolatedPositionMode_DllExport + #define PositionMode_DllExport + #define VelocityMode_DllExport + #define CurrentMode_DllExport + #define MasterEncoderMode_DllExport + #define StepDirectionMode_DllExport + #define InputsOutputs_DllExport + #define DataRecording_DllExport + #define CanLayer_DllExport +#endif // _WIN32 +#endif // EposDllExports + #ifdef __cplusplus extern "C" { #endif @@ -17,517 +69,517 @@ int DeleteDataRecorderCmdManager(); *************************************************************************************************************************************/ //Communication -void* VCS_OpenDevice(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, unsigned int* pErrorCode); -int VCS_SetProtocolStackSettings(void* KeyHandle, unsigned int Baudrate, unsigned int Timeout, unsigned int* pErrorCode); -int VCS_GetProtocolStackSettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pTimeout, unsigned int* pErrorCode); -int VCS_CloseDevice(void* KeyHandle, unsigned int* pErrorCode); -int VCS_CloseAllDevices(unsigned int* pErrorCode); + Initialisation_DllExport void* VCS_OpenDevice(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_SetProtocolStackSettings(void* KeyHandle, unsigned int Baudrate, unsigned int Timeout, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_GetProtocolStackSettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pTimeout, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_CloseDevice(void* KeyHandle, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_CloseAllDevices(unsigned int* pErrorCode); //Gateway -int VCS_SetGatewaySettings(void* KeyHandle, unsigned int Baudrate, unsigned int* pErrorCode); -int VCS_GetGatewaySettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_SetGatewaySettings(void* KeyHandle, unsigned int Baudrate, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_GetGatewaySettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pErrorCode); //Sub device -void* VCS_OpenSubDevice(void* DeviceHandle, char* DeviceName, char* ProtocolStackName, unsigned int* pErrorCode); -int VCS_CloseSubDevice(void* KeyHandle, unsigned int* pErrorCode); -int VCS_CloseAllSubDevices(void* DeviceHandle, unsigned int* pErrorCode); + Initialisation_DllExport void* VCS_OpenSubDevice(void* DeviceHandle, char* DeviceName, char* ProtocolStackName, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_CloseSubDevice(void* KeyHandle, unsigned int* pErrorCode); + Initialisation_DllExport int VCS_CloseAllSubDevices(void* DeviceHandle, unsigned int* pErrorCode); //Info -int VCS_GetDriverInfo(char* p_pszLibraryName, unsigned short p_usMaxLibraryNameStrSize,char* p_pszLibraryVersion, unsigned short p_usMaxLibraryVersionStrSize, unsigned int* p_pErrorCode); -int VCS_GetVersion(void* KeyHandle, unsigned short NodeId, unsigned short* pHardwareVersion, unsigned short* pSoftwareVersion, unsigned short* pApplicationNumber, unsigned short* pApplicationVersion, unsigned int* pErrorCode); -int VCS_GetErrorInfo(unsigned int ErrorCodeValue, char* pErrorInfo, unsigned short MaxStrSize); + HelpFunctions_DllExport int VCS_GetDriverInfo(char* p_pszLibraryName, unsigned short p_usMaxLibraryNameStrSize,char* p_pszLibraryVersion, unsigned short p_usMaxLibraryVersionStrSize, unsigned int* p_pErrorCode); + 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); + HelpFunctions_DllExport int VCS_GetErrorInfo(unsigned int ErrorCodeValue, char* pErrorInfo, unsigned short MaxStrSize); //Advanced Functions -int VCS_GetDeviceNameSelection(int StartOfSelection, char* pDeviceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); -int VCS_GetProtocolStackNameSelection(char* DeviceName, int StartOfSelection, char* pProtocolStackNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); -int VCS_GetInterfaceNameSelection(char* DeviceName, char* ProtocolStackName, int StartOfSelection, char* pInterfaceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); -int VCS_GetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, int StartOfSelection, char* pPortSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); -int VCS_ResetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, unsigned int* pErrorCode); -int VCS_GetBaudrateSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, int StartOfSelection, unsigned int* pBaudrateSel, int* pEndOfSelection, unsigned int* pErrorCode); -int VCS_GetKeyHandle(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, void** pKeyHandle, unsigned int* pErrorCode); -int VCS_GetDeviceName(void* KeyHandle, char* pDeviceName, unsigned short MaxStrSize, unsigned int* pErrorCode); -int VCS_GetProtocolStackName(void* KeyHandle, char* pProtocolStackName, unsigned short MaxStrSize, unsigned int* pErrorCode); -int VCS_GetInterfaceName(void* KeyHandle, char* pInterfaceName, unsigned short MaxStrSize, unsigned int* pErrorCode); -int VCS_GetPortName(void* KeyHandle, char* pPortName, unsigned short MaxStrSize, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetDeviceNameSelection(int StartOfSelection, char* pDeviceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetProtocolStackNameSelection(char* DeviceName, int StartOfSelection, char* pProtocolStackNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetInterfaceNameSelection(char* DeviceName, char* ProtocolStackName, int StartOfSelection, char* pInterfaceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, int StartOfSelection, char* pPortSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_ResetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetBaudrateSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, int StartOfSelection, unsigned int* pBaudrateSel, int* pEndOfSelection, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetKeyHandle(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, void** pKeyHandle, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetDeviceName(void* KeyHandle, char* pDeviceName, unsigned short MaxStrSize, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetProtocolStackName(void* KeyHandle, char* pProtocolStackName, unsigned short MaxStrSize, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetInterfaceName(void* KeyHandle, char* pInterfaceName, unsigned short MaxStrSize, unsigned int* pErrorCode); + HelpFunctions_DllExport int VCS_GetPortName(void* KeyHandle, char* pPortName, unsigned short MaxStrSize, unsigned int* pErrorCode); /************************************************************************************************************************************* * CONFIGURATION FUNCTIONS *************************************************************************************************************************************/ //General -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); -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); -int VCS_Restore(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_Store(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + 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); + 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); + Configuration_DllExport int VCS_Restore(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + Configuration_DllExport int VCS_Store(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Advanced Functions -//Motor -int VCS_SetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short MotorType, unsigned int* pErrorCode); -int VCS_SetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short NominalCurrent, unsigned short MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); -int VCS_SetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); -int VCS_SetEcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short NominalCurrent, unsigned short MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned char NbOfPolePairs, unsigned int* pErrorCode); -int VCS_SetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned char NbOfPolePairs, unsigned int* pErrorCode); -int VCS_GetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short* pMotorType, unsigned int* pErrorCode); -int VCS_GetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pNominalCurrent, unsigned short* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); -int VCS_GetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); -int VCS_GetEcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pNominalCurrent, unsigned short* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned char* pNbOfPolePairs, unsigned int* pErrorCode); -int VCS_GetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned char* pNbOfPolePairs, unsigned int* pErrorCode); - -//Sensor -int VCS_SetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short SensorType, unsigned int* pErrorCode); -int VCS_SetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int EncoderResolution, int InvertedPolarity, unsigned int* pErrorCode); -int VCS_SetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int InvertedPolarity, unsigned int* pErrorCode); -int VCS_SetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, int InvertedPolarity, unsigned int* pErrorCode); -int VCS_SetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSpecialDataBits, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, unsigned int* pErrorCode); -int VCS_SetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfSpecialDataBitsLeading, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfMultiTurnPositionBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSingleTurnPositionBits, unsigned short NbOfSpecialDataBitsTrailing, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, int CheckFrame, int ReferenceReset, unsigned int* pErrorCode); -int VCS_GetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short* pSensorType, unsigned int* pErrorCode); -int VCS_GetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pEncoderResolution, int* pInvertedPolarity, unsigned int* pErrorCode); -int VCS_GetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int* pInvertedPolarity, unsigned int* pErrorCode); -int VCS_GetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, int* pInvertedPolarity, unsigned int* pErrorCode); -int VCS_GetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSpecialDataBits, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, unsigned int* pErrorCode); -int VCS_GetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfSpecialDataBitsLeading, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfMultiTurnPositionBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSingleTurnPositionBits, unsigned short* pNbOfSpecialDataBitsTrailing, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, int* pCheckFrame, int* pReferenceReset, unsigned int* pErrorCode); - -//Safety -int VCS_SetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int MaxFollowingError, unsigned int* pErrorCode); -int VCS_GetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxFollowingError, unsigned int* pErrorCode); -int VCS_SetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int MaxProfileVelocity, unsigned int* pErrorCode); -int VCS_GetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxProfileVelocity, unsigned int* pErrorCode); -int VCS_SetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int MaxAcceleration, unsigned int* pErrorCode); -int VCS_GetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxAcceleration, unsigned int* pErrorCode); - -//Controller Gains -int VCS_SetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long Value, unsigned int* pErrorCode); -int VCS_GetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long* pValue, unsigned int* pErrorCode); - -//Inputs/Outputs -int VCS_DigitalInputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNb, unsigned short Configuration, int Mask, int Polarity, int ExecutionMask, unsigned int* pErrorCode); -int VCS_DigitalOutputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNb, unsigned short Configuration, int State, int Mask, int Polarity, unsigned int* pErrorCode); -int VCS_AnalogInputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNb, unsigned short Configuration, int ExecutionMask, unsigned int* pErrorCode); -int VCS_AnalogOutputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogOutputNb, unsigned short Configuration, unsigned int* pErrorCode); - -//Units -int VCS_SetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char VelDimension, signed char VelNotation, unsigned int* pErrorCode); -int VCS_GetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char* pVelDimension, char* pVelNotation, unsigned int* pErrorCode); - -//Compatibility Functions (do not use) -int VCS_SetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned short D, unsigned int* pErrorCode); -int VCS_SetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); -int VCS_GetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned short* pD, unsigned int* pErrorCode); -int VCS_GetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); - -int VCS_SetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); -int VCS_SetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); -int VCS_GetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); -int VCS_GetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); - -int VCS_SetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); -int VCS_GetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); + //Motor + Configuration_DllExport int VCS_SetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short MotorType, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short NominalCurrent, unsigned short MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); + 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); + Configuration_DllExport int VCS_SetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned char NbOfPolePairs, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short* pMotorType, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pNominalCurrent, unsigned short* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); + 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); + Configuration_DllExport int VCS_GetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned char* pNbOfPolePairs, unsigned int* pErrorCode); + + //Sensor + Configuration_DllExport int VCS_SetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short SensorType, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int EncoderResolution, int InvertedPolarity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int InvertedPolarity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, int InvertedPolarity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSpecialDataBits, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfSpecialDataBitsLeading, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfMultiTurnPositionBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSingleTurnPositionBits, unsigned short NbOfSpecialDataBitsTrailing, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, int CheckFrame, int ReferenceReset, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short* pSensorType, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pEncoderResolution, int* pInvertedPolarity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int* pInvertedPolarity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, int* pInvertedPolarity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSpecialDataBits, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfSpecialDataBitsLeading, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfMultiTurnPositionBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSingleTurnPositionBits, unsigned short* pNbOfSpecialDataBitsTrailing, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, int* pCheckFrame, int* pReferenceReset, unsigned int* pErrorCode); + + //Safety + Configuration_DllExport int VCS_SetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int MaxFollowingError, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxFollowingError, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int MaxProfileVelocity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxProfileVelocity, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int MaxAcceleration, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxAcceleration, unsigned int* pErrorCode); + + //Controller Gains + Configuration_DllExport int VCS_SetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long Value, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long* pValue, unsigned int* pErrorCode); + + //Inputs/Outputs + 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); + 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); + Configuration_DllExport int VCS_AnalogInputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNb, unsigned short Configuration, int ExecutionMask, unsigned int* pErrorCode); + Configuration_DllExport int VCS_AnalogOutputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogOutputNb, unsigned short Configuration, unsigned int* pErrorCode); + + //Units + Configuration_DllExport int VCS_SetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char VelDimension, signed char VelNotation, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char* pVelDimension, char* pVelNotation, unsigned int* pErrorCode); + + //Compatibility Functions (do not use) + Configuration_DllExport int VCS_SetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned short D, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned short* pD, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); + + Configuration_DllExport int VCS_SetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); + Configuration_DllExport int VCS_SetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); + + Configuration_DllExport int VCS_SetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); + Configuration_DllExport int VCS_GetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); /************************************************************************************************************************************* * OPERATION FUNCTIONS *************************************************************************************************************************************/ //OperationMode -int VCS_SetOperationMode(void* KeyHandle, unsigned short NodeId, char OperationMode, unsigned int* pErrorCode); -int VCS_GetOperationMode(void* KeyHandle, unsigned short NodeId, char* pOperationMode, unsigned int* pErrorCode); + Status_DllExport int VCS_SetOperationMode(void* KeyHandle, unsigned short NodeId, char OperationMode, unsigned int* pErrorCode); + Status_DllExport int VCS_GetOperationMode(void* KeyHandle, unsigned short NodeId, char* pOperationMode, unsigned int* pErrorCode); //StateMachine -int VCS_ResetDevice(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetState(void* KeyHandle, unsigned short NodeId, unsigned short State, unsigned int* pErrorCode); -int VCS_SetEnableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetDisableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetQuickStopState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_ClearFault(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_GetState(void* KeyHandle, unsigned short NodeId, unsigned short* pState, unsigned int* pErrorCode); -int VCS_GetEnableState(void* KeyHandle, unsigned short NodeId, int* pIsEnabled, unsigned int* pErrorCode); -int VCS_GetDisableState(void* KeyHandle, unsigned short NodeId, int* pIsDisabled, unsigned int* pErrorCode); -int VCS_GetQuickStopState(void* KeyHandle, unsigned short NodeId, int* pIsQuickStopped, unsigned int* pErrorCode); -int VCS_GetFaultState(void* KeyHandle, unsigned short NodeId, int* pIsInFault, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_ResetDevice(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_SetState(void* KeyHandle, unsigned short NodeId, unsigned short State, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_SetEnableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_SetDisableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_SetQuickStopState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_ClearFault(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_GetState(void* KeyHandle, unsigned short NodeId, unsigned short* pState, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_GetEnableState(void* KeyHandle, unsigned short NodeId, int* pIsEnabled, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_GetDisableState(void* KeyHandle, unsigned short NodeId, int* pIsDisabled, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_GetQuickStopState(void* KeyHandle, unsigned short NodeId, int* pIsQuickStopped, unsigned int* pErrorCode); + StateMachine_DllExport int VCS_GetFaultState(void* KeyHandle, unsigned short NodeId, int* pIsInFault, unsigned int* pErrorCode); //ErrorHandling -int VCS_GetNbOfDeviceError(void* KeyHandle, unsigned short NodeId, unsigned char *pNbDeviceError, unsigned int *pErrorCode); -int VCS_GetDeviceErrorCode(void* KeyHandle, unsigned short NodeId, unsigned char DeviceErrorNumber, unsigned int *pDeviceErrorCode, unsigned int *pErrorCode); + ErrorHandling_DllExport int VCS_GetNbOfDeviceError(void* KeyHandle, unsigned short NodeId, unsigned char *pNbDeviceError, unsigned int *pErrorCode); + ErrorHandling_DllExport int VCS_GetDeviceErrorCode(void* KeyHandle, unsigned short NodeId, unsigned char DeviceErrorNumber, unsigned int *pDeviceErrorCode, unsigned int *pErrorCode); //Motion Info -int VCS_GetMovementState(void* KeyHandle, unsigned short NodeId, int* pTargetReached, unsigned int* pErrorCode); -int VCS_GetPositionIs(void* KeyHandle, unsigned short NodeId, int* pPositionIs, unsigned int* pErrorCode); -int VCS_GetVelocityIs(void* KeyHandle, unsigned short NodeId, int* pVelocityIs, unsigned int* pErrorCode); -int VCS_GetVelocityIsAveraged(void* KeyHandle, unsigned short NodeId, int* pVelocityIsAveraged, unsigned int* pErrorCode); -int VCS_GetCurrentIs(void* KeyHandle, unsigned short NodeId, short* pCurrentIs, unsigned int* pErrorCode); -int VCS_GetCurrentIsEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIs, unsigned int* pErrorCode); -int VCS_GetCurrentIsAveraged(void* KeyHandle, unsigned short NodeId, short* pCurrentIsAveraged, unsigned int* pErrorCode); -int VCS_GetCurrentIsAveragedEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIsAveraged, unsigned int* pErrorCode); -int VCS_WaitForTargetReached(void* KeyHandle, unsigned short NodeId, unsigned int Timeout, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetMovementState(void* KeyHandle, unsigned short NodeId, int* pTargetReached, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetPositionIs(void* KeyHandle, unsigned short NodeId, int* pPositionIs, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetVelocityIs(void* KeyHandle, unsigned short NodeId, int* pVelocityIs, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetVelocityIsAveraged(void* KeyHandle, unsigned short NodeId, int* pVelocityIsAveraged, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetCurrentIs(void* KeyHandle, unsigned short NodeId, short* pCurrentIs, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetCurrentIsEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIs, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetCurrentIsAveraged(void* KeyHandle, unsigned short NodeId, short* pCurrentIsAveraged, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_GetCurrentIsAveragedEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIsAveraged, unsigned int* pErrorCode); + MotionInfo_DllExport int VCS_WaitForTargetReached(void* KeyHandle, unsigned short NodeId, unsigned int Timeout, unsigned int* pErrorCode); //Profile Position Mode -int VCS_ActivateProfilePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileVelocity, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); -int VCS_GetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileVelocity, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); -int VCS_MoveToPosition(void* KeyHandle, unsigned short NodeId, long TargetPosition, int Absolute, int Immediately, unsigned int* pErrorCode); -int VCS_GetTargetPosition(void* KeyHandle, unsigned short NodeId, long* pTargetPosition, unsigned int* pErrorCode); -int VCS_HaltPositionMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + ProfilePositionMode_DllExport int VCS_ActivateProfilePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + ProfilePositionMode_DllExport int VCS_SetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileVelocity, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); + ProfilePositionMode_DllExport int VCS_GetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileVelocity, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); + ProfilePositionMode_DllExport int VCS_MoveToPosition(void* KeyHandle, unsigned short NodeId, long TargetPosition, int Absolute, int Immediately, unsigned int* pErrorCode); + ProfilePositionMode_DllExport int VCS_GetTargetPosition(void* KeyHandle, unsigned short NodeId, long* pTargetPosition, unsigned int* pErrorCode); + ProfilePositionMode_DllExport int VCS_HaltPositionMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -//Advanced Functions -int VCS_EnablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int PositionWindow, unsigned short PositionWindowTime, unsigned int* pErrorCode); -int VCS_DisablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + //Advanced Functions + ProfilePositionMode_DllExport int VCS_EnablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int PositionWindow, unsigned short PositionWindowTime, unsigned int* pErrorCode); + ProfilePositionMode_DllExport int VCS_DisablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Profile Velocity Mode -int VCS_ActivateProfileVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); -int VCS_GetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); -int VCS_MoveWithVelocity(void* KeyHandle, unsigned short NodeId, long TargetVelocity, unsigned int* pErrorCode); -int VCS_GetTargetVelocity(void* KeyHandle, unsigned short NodeId, long* pTargetVelocity, unsigned int* pErrorCode); -int VCS_HaltVelocityMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + ProfileVelocityMode_DllExport int VCS_ActivateProfileVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + ProfileVelocityMode_DllExport int VCS_SetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); + ProfileVelocityMode_DllExport int VCS_GetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); + ProfileVelocityMode_DllExport int VCS_MoveWithVelocity(void* KeyHandle, unsigned short NodeId, long TargetVelocity, unsigned int* pErrorCode); + ProfileVelocityMode_DllExport int VCS_GetTargetVelocity(void* KeyHandle, unsigned short NodeId, long* pTargetVelocity, unsigned int* pErrorCode); + ProfileVelocityMode_DllExport int VCS_HaltVelocityMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -//Advanced Functions -int VCS_EnableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int VelocityWindow, unsigned short VelocityWindowTime, unsigned int* pErrorCode); -int VCS_DisableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + //Advanced Functions + ProfileVelocityMode_DllExport int VCS_EnableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int VelocityWindow, unsigned short VelocityWindowTime, unsigned int* pErrorCode); + ProfileVelocityMode_DllExport int VCS_DisableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Homing Mode -int VCS_ActivateHomingMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int HomingAcceleration, unsigned int SpeedSwitch, unsigned int SpeedIndex, int HomeOffset, unsigned short CurrentThreshold, int HomePosition, unsigned int* pErrorCode); -int VCS_GetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pHomingAcceleration, unsigned int* pSpeedSwitch, unsigned int* pSpeedIndex, int* pHomeOffset, unsigned short* pCurrentThreshold, int* pHomePosition, unsigned int* pErrorCode); -int VCS_FindHome(void* KeyHandle, unsigned short NodeId, signed char HomingMethod, unsigned int* pErrorCode); -int VCS_StopHoming(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_DefinePosition(void* KeyHandle, unsigned short NodeId, int HomePosition, unsigned int* pErrorCode); -int VCS_WaitForHomingAttained(void* KeyHandle, unsigned short NodeId, int Timeout, unsigned int* pErrorCode); -int VCS_GetHomingState(void* KeyHandle, unsigned short NodeId, int* pHomingAttained, int* pHomingError, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_ActivateHomingMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_SetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int HomingAcceleration, unsigned int SpeedSwitch, unsigned int SpeedIndex, int HomeOffset, unsigned short CurrentThreshold, int HomePosition, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_GetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pHomingAcceleration, unsigned int* pSpeedSwitch, unsigned int* pSpeedIndex, int* pHomeOffset, unsigned short* pCurrentThreshold, int* pHomePosition, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_FindHome(void* KeyHandle, unsigned short NodeId, signed char HomingMethod, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_StopHoming(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_DefinePosition(void* KeyHandle, unsigned short NodeId, int HomePosition, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_WaitForHomingAttained(void* KeyHandle, unsigned short NodeId, int Timeout, unsigned int* pErrorCode); + HomingMode_DllExport int VCS_GetHomingState(void* KeyHandle, unsigned short NodeId, int* pHomingAttained, int* pHomingError, unsigned int* pErrorCode); //Interpolated Position Mode -int VCS_ActivateInterpolatedPositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short UnderflowWarningLimit, unsigned short OverflowWarningLimit, unsigned int* pErrorCode); -int VCS_GetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pUnderflowWarningLimit, unsigned short* pOverflowWarningLimit, unsigned int* pMaxBufferSize, unsigned int* pErrorCode); -int VCS_ClearIpmBuffer(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_GetFreeIpmBufferSize(void* KeyHandle, unsigned short NodeId, unsigned int* pBufferSize, unsigned int* pErrorCode); -int VCS_AddPvtValueToIpmBuffer(void* KeyHandle, unsigned short NodeId, long Position, long Velocity, unsigned char Time, unsigned int* pErrorCode); -int VCS_StartIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_StopIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -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); + InterpolatedPositionMode_DllExport int VCS_ActivateInterpolatedPositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + InterpolatedPositionMode_DllExport int VCS_SetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short UnderflowWarningLimit, unsigned short OverflowWarningLimit, unsigned int* pErrorCode); + InterpolatedPositionMode_DllExport int VCS_GetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pUnderflowWarningLimit, unsigned short* pOverflowWarningLimit, unsigned int* pMaxBufferSize, unsigned int* pErrorCode); + InterpolatedPositionMode_DllExport int VCS_ClearIpmBuffer(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + InterpolatedPositionMode_DllExport int VCS_GetFreeIpmBufferSize(void* KeyHandle, unsigned short NodeId, unsigned int* pBufferSize, unsigned int* pErrorCode); + InterpolatedPositionMode_DllExport int VCS_AddPvtValueToIpmBuffer(void* KeyHandle, unsigned short NodeId, long Position, long Velocity, unsigned char Time, unsigned int* pErrorCode); + InterpolatedPositionMode_DllExport int VCS_StartIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + InterpolatedPositionMode_DllExport int VCS_StopIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + 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); //Position Mode -int VCS_ActivatePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetPositionMust(void* KeyHandle, unsigned short NodeId, long PositionMust, unsigned int* pErrorCode); -int VCS_GetPositionMust(void* KeyHandle, unsigned short NodeId, long* pPositionMust, unsigned int* pErrorCode); + PositionMode_DllExport int VCS_ActivatePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + PositionMode_DllExport int VCS_SetPositionMust(void* KeyHandle, unsigned short NodeId, long PositionMust, unsigned int* pErrorCode); + PositionMode_DllExport int VCS_GetPositionMust(void* KeyHandle, unsigned short NodeId, long* pPositionMust, unsigned int* pErrorCode); -//Advanced Functions -int VCS_ActivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); -int VCS_DeactivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); -int VCS_EnableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_DisableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + //Advanced Functions + PositionMode_DllExport int VCS_ActivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); + PositionMode_DllExport int VCS_DeactivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); + PositionMode_DllExport int VCS_EnableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + PositionMode_DllExport int VCS_DisableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Velocity Mode -int VCS_ActivateVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetVelocityMust(void* KeyHandle, unsigned short NodeId, long VelocityMust, unsigned int* pErrorCode); -int VCS_GetVelocityMust(void* KeyHandle, unsigned short NodeId, long* pVelocityMust, unsigned int* pErrorCode); + VelocityMode_DllExport int VCS_ActivateVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + VelocityMode_DllExport int VCS_SetVelocityMust(void* KeyHandle, unsigned short NodeId, long VelocityMust, unsigned int* pErrorCode); + VelocityMode_DllExport int VCS_GetVelocityMust(void* KeyHandle, unsigned short NodeId, long* pVelocityMust, unsigned int* pErrorCode); -//Advanced Functions -int VCS_ActivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); -int VCS_DeactivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); -int VCS_EnableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_DisableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + //Advanced Functions + VelocityMode_DllExport int VCS_ActivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); + VelocityMode_DllExport int VCS_DeactivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); + VelocityMode_DllExport int VCS_EnableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + VelocityMode_DllExport int VCS_DisableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Current Mode -int VCS_ActivateCurrentMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetCurrentMust(void* KeyHandle, unsigned short NodeId, short CurrentMust, unsigned int* pErrorCode); -int VCS_SetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int CurrentMust, unsigned int* pErrorCode); -int VCS_GetCurrentMust(void* KeyHandle, unsigned short NodeId, short* pCurrentMust, unsigned int* pErrorCode); -int VCS_GetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int* pCurrentMust, unsigned int* pErrorCode); - -//Advanced Functions -int VCS_ActivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, short Offset, unsigned int* pErrorCode); -int VCS_DeactivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); -int VCS_EnableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_DisableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_ActivateCurrentMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_SetCurrentMust(void* KeyHandle, unsigned short NodeId, short CurrentMust, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_SetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int CurrentMust, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_GetCurrentMust(void* KeyHandle, unsigned short NodeId, short* pCurrentMust, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_GetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int* pCurrentMust, unsigned int* pErrorCode); + + //Advanced Functions + CurrentMode_DllExport int VCS_ActivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, short Offset, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_DeactivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_EnableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + CurrentMode_DllExport int VCS_DisableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //MasterEncoder Mode -int VCS_ActivateMasterEncoderMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -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); -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); + MasterEncoderMode_DllExport int VCS_ActivateMasterEncoderMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + 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); + 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); //StepDirection Mode -int VCS_ActivateStepDirectionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -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); -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); + StepDirectionMode_DllExport int VCS_ActivateStepDirectionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + 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); + 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); //Inputs Outputs -//General -int VCS_GetAllDigitalInputs(void* KeyHandle, unsigned short NodeId, unsigned short* pInputs, unsigned int* pErrorCode); -int VCS_GetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short* pOutputs, unsigned int* pErrorCode); -int VCS_SetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short Outputs, unsigned int* pErrorCode); -int VCS_GetAnalogInput(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, unsigned short* pAnalogValue, unsigned int* pErrorCode); -int VCS_GetAnalogInputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, long* pVoltageValue, unsigned int* pErrorCode); -int VCS_GetAnalogInputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long* pStateValue, unsigned int* pErrorCode); -int VCS_SetAnalogOutput(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, unsigned short AnalogValue, unsigned int* pErrorCode); -int VCS_SetAnalogOutputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, long VoltageValue, unsigned int* pErrorCode); -int VCS_SetAnalogOutputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long StateValue, unsigned int* pErrorCode); - -//Position Compare -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); -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); -int VCS_ActivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, int Polarity, unsigned int* pErrorCode); -int VCS_DeactivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, unsigned int* pErrorCode); -int VCS_EnablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_DisablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_SetPositionCompareReferencePosition(void* KeyHandle, unsigned short NodeId, long ReferencePosition, unsigned int* pErrorCode); - -//Position Marker -int VCS_SetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char PositionMarkerEdgeType, unsigned char PositionMarkerMode, unsigned int* pErrorCode); -int VCS_GetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char* pPositionMarkerEdgeType, unsigned char* pPositionMarkerMode, unsigned int* pErrorCode); -int VCS_ActivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, int Polarity, unsigned int* pErrorCode); -int VCS_DeactivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, unsigned int* pErrorCode); -int VCS_ReadPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned short* pCount, unsigned int* pErrorCode); -int VCS_ReadPositionMarkerCapturedPosition(void* KeyHandle, unsigned short NodeId, unsigned short CounterIndex, long* pCapturedPosition, unsigned int* pErrorCode); -int VCS_ResetPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + //General + InputsOutputs_DllExport int VCS_GetAllDigitalInputs(void* KeyHandle, unsigned short NodeId, unsigned short* pInputs, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_GetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short* pOutputs, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_SetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short Outputs, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_GetAnalogInput(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, unsigned short* pAnalogValue, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_GetAnalogInputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, long* pVoltageValue, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_GetAnalogInputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long* pStateValue, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_SetAnalogOutput(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, unsigned short AnalogValue, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_SetAnalogOutputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, long VoltageValue, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_SetAnalogOutputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long StateValue, unsigned int* pErrorCode); + + //Position Compare + 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); + 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); + InputsOutputs_DllExport int VCS_ActivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, int Polarity, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_DeactivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_EnablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_DisablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_SetPositionCompareReferencePosition(void* KeyHandle, unsigned short NodeId, long ReferencePosition, unsigned int* pErrorCode); + + //Position Marker + InputsOutputs_DllExport int VCS_SetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char PositionMarkerEdgeType, unsigned char PositionMarkerMode, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_GetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char* pPositionMarkerEdgeType, unsigned char* pPositionMarkerMode, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_ActivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, int Polarity, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_DeactivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_ReadPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned short* pCount, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_ReadPositionMarkerCapturedPosition(void* KeyHandle, unsigned short NodeId, unsigned short CounterIndex, long* pCapturedPosition, unsigned int* pErrorCode); + InputsOutputs_DllExport int VCS_ResetPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //******************************************************************************************************************* // DATA RECORDING FUNCTIONS //******************************************************************************************************************* -//DataRecorder Setup -int VCS_SetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short SamplingPeriod, unsigned short NbOfPrecedingSamples, unsigned int* pErrorCode); -int VCS_GetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pSamplingPeriod, unsigned short* pNbOfPrecedingSamples, unsigned int* pErrorCode); -int VCS_EnableTrigger(void* KeyHandle, unsigned short NodeId, unsigned char TriggerType, unsigned int* pErrorCode); -int VCS_DisableAllTriggers(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_ActivateChannel(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned short ObjectIndex, unsigned char ObjectSubIndex, unsigned char ObjectSize, unsigned int* pErrorCode); -int VCS_DeactivateAllChannels(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - -//DataRecorder Status -int VCS_StartRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_StopRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_ForceTrigger(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); -int VCS_IsRecorderRunning(void* KeyHandle, unsigned short NodeId, int* pRunning, unsigned int* pErrorCode); -int VCS_IsRecorderTriggered(void* KeyHandle, unsigned short NodeId, int* pTriggered, unsigned int* pErrorCode); - -//DataRecorder Data -int VCS_ReadChannelVectorSize(void* KeyHandle, unsigned short NodeId, unsigned int* pVectorSize, unsigned int* pErrorCode); -int VCS_ReadChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataVectorBuffer, unsigned int VectorBufferSize, unsigned int* pErrorCode); - -//Advanced Functions -int VCS_ReadDataBuffer(void* KeyHandle, unsigned short NodeId, unsigned char* pDataBuffer, unsigned int BufferSizeToRead, unsigned int* pBufferSizeRead, unsigned short* pVectorStartOffset, unsigned short* pMaxNbOfSamples, unsigned short* pNbOfRecordedSamples, unsigned int* pErrorCode); -int VCS_ExtractChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataBuffer, unsigned int BufferSize, unsigned char* pDataVector, unsigned int VectorSize, unsigned short VectorStartOffset, unsigned short MaxNbOfSamples, unsigned short NbOfRecordedSamples, unsigned int* pErrorCode); + //DataRecorder Setup + DataRecording_DllExport int VCS_SetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short SamplingPeriod, unsigned short NbOfPrecedingSamples, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_GetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pSamplingPeriod, unsigned short* pNbOfPrecedingSamples, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_EnableTrigger(void* KeyHandle, unsigned short NodeId, unsigned char TriggerType, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_DisableAllTriggers(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_ActivateChannel(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned short ObjectIndex, unsigned char ObjectSubIndex, unsigned char ObjectSize, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_DeactivateAllChannels(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + + //DataRecorder Status + DataRecording_DllExport int VCS_StartRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_StopRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_ForceTrigger(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_IsRecorderRunning(void* KeyHandle, unsigned short NodeId, int* pRunning, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_IsRecorderTriggered(void* KeyHandle, unsigned short NodeId, int* pTriggered, unsigned int* pErrorCode); + + //DataRecorder Data + DataRecording_DllExport int VCS_ReadChannelVectorSize(void* KeyHandle, unsigned short NodeId, unsigned int* pVectorSize, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_ReadChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataVectorBuffer, unsigned int VectorBufferSize, unsigned int* pErrorCode); + + //Advanced Functions + DataRecording_DllExport int VCS_ReadDataBuffer(void* KeyHandle, unsigned short NodeId, unsigned char* pDataBuffer, unsigned int BufferSizeToRead, unsigned int* pBufferSizeRead, unsigned short* pVectorStartOffset, unsigned short* pMaxNbOfSamples, unsigned short* pNbOfRecordedSamples, unsigned int* pErrorCode); + DataRecording_DllExport int VCS_ExtractChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataBuffer, unsigned int BufferSize, unsigned char* pDataVector, unsigned int VectorSize, unsigned short VectorStartOffset, unsigned short MaxNbOfSamples, unsigned short NbOfRecordedSamples, unsigned int* pErrorCode); /************************************************************************************************************************************* * LOW LAYER FUNCTIONS *************************************************************************************************************************************/ //CanLayer Functions -int VCS_SendCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); -int VCS_ReadCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int Timeout, unsigned int* pErrorCode); -int VCS_RequestCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); -int VCS_SendNMTService(void* KeyHandle, unsigned short NodeId, unsigned short CommandSpecifier, unsigned int* pErrorCode); + CanLayer_DllExport int VCS_SendCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); + CanLayer_DllExport int VCS_ReadCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int Timeout, unsigned int* pErrorCode); + CanLayer_DllExport int VCS_RequestCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); + CanLayer_DllExport int VCS_SendNMTService(void* KeyHandle, unsigned short NodeId, unsigned short CommandSpecifier, unsigned int* pErrorCode); /************************************************************************************************************************************* * TYPE DEFINITIONS *************************************************************************************************************************************/ //Communication -//Dialog Mode -const int DM_PROGRESS_DLG = 0; -const int DM_PROGRESS_AND_CONFIRM_DLG = 1; -const int DM_CONFIRM_DLG = 2; -const int DM_NO_DLG = 3; + //Dialog Mode + const int DM_PROGRESS_DLG = 0; + const int DM_PROGRESS_AND_CONFIRM_DLG = 1; + const int DM_CONFIRM_DLG = 2; + const int DM_NO_DLG = 3; //Configuration -//MotorType -const unsigned short MT_DC_MOTOR = 1; -const unsigned short MT_EC_SINUS_COMMUTATED_MOTOR = 10; -const unsigned short MT_EC_BLOCK_COMMUTATED_MOTOR = 11; - -//SensorType -const unsigned short ST_UNKNOWN = 0; -const unsigned short ST_INC_ENCODER_3CHANNEL = 1; -const unsigned short ST_INC_ENCODER_2CHANNEL = 2; -const unsigned short ST_HALL_SENSORS = 3; -const unsigned short ST_SSI_ABS_ENCODER_BINARY = 4; -const unsigned short ST_SSI_ABS_ENCODER_GREY = 5; -const unsigned short ST_INC_ENCODER2_3CHANNEL = 6; -const unsigned short ST_INC_ENCODER2_2CHANNEL = 7; -const unsigned short ST_ANALOG_INC_ENCODER_3CHANNEL = 8; -const unsigned short ST_ANALOG_INC_ENCODER_2CHANNEL = 9; + //MotorType + const unsigned short MT_DC_MOTOR = 1; + const unsigned short MT_EC_SINUS_COMMUTATED_MOTOR = 10; + const unsigned short MT_EC_BLOCK_COMMUTATED_MOTOR = 11; + + //SensorType + const unsigned short ST_UNKNOWN = 0; + const unsigned short ST_INC_ENCODER_3CHANNEL = 1; + const unsigned short ST_INC_ENCODER_2CHANNEL = 2; + const unsigned short ST_HALL_SENSORS = 3; + const unsigned short ST_SSI_ABS_ENCODER_BINARY = 4; + const unsigned short ST_SSI_ABS_ENCODER_GREY = 5; + const unsigned short ST_INC_ENCODER2_3CHANNEL = 6; + const unsigned short ST_INC_ENCODER2_2CHANNEL = 7; + const unsigned short ST_ANALOG_INC_ENCODER_3CHANNEL = 8; + const unsigned short ST_ANALOG_INC_ENCODER_2CHANNEL = 9; //In- and outputs -//Digital input configuration -const unsigned short DIC_NEGATIVE_LIMIT_SWITCH = 0; -const unsigned short DIC_POSITIVE_LIMIT_SWITCH = 1; -const unsigned short DIC_HOME_SWITCH = 2; -const unsigned short DIC_POSITION_MARKER = 3; -const unsigned short DIC_DRIVE_ENABLE = 4; -const unsigned short DIC_QUICK_STOP = 5; -const unsigned short DIC_GENERAL_PURPOSE_J = 6; -const unsigned short DIC_GENERAL_PURPOSE_I = 7; -const unsigned short DIC_GENERAL_PURPOSE_H = 8; -const unsigned short DIC_GENERAL_PURPOSE_G = 9; -const unsigned short DIC_GENERAL_PURPOSE_F = 10; -const unsigned short DIC_GENERAL_PURPOSE_E = 11; -const unsigned short DIC_GENERAL_PURPOSE_D = 12; -const unsigned short DIC_GENERAL_PURPOSE_C = 13; -const unsigned short DIC_GENERAL_PURPOSE_B = 14; -const unsigned short DIC_GENERAL_PURPOSE_A = 15; - -//Digital output configuration -const unsigned short DOC_READY_FAULT = 0; -const unsigned short DOC_POSITION_COMPARE = 1; -const unsigned short DOC_GENERAL_PURPOSE_H = 8; -const unsigned short DOC_GENERAL_PURPOSE_G = 9; -const unsigned short DOC_GENERAL_PURPOSE_F = 10; -const unsigned short DOC_GENERAL_PURPOSE_E = 11; -const unsigned short DOC_GENERAL_PURPOSE_D = 12; -const unsigned short DOC_GENERAL_PURPOSE_C = 13; -const unsigned short DOC_GENERAL_PURPOSE_B = 14; -const unsigned short DOC_GENERAL_PURPOSE_A = 15; - -//Analog input configuration -const unsigned short AIC_ANALOG_CURRENT_SETPOINT = 0; -const unsigned short AIC_ANALOG_VELOCITY_SETPOINT = 1; -const unsigned short AIC_ANALOG_POSITION_SETPOINT = 2; -const unsigned short AIC_GENERAL_PURPOSE_H = 8; -const unsigned short AIC_GENERAL_PURPOSE_G = 9; -const unsigned short AIC_GENERAL_PURPOSE_F = 10; -const unsigned short AIC_GENERAL_PURPOSE_E = 11; -const unsigned short AIC_GENERAL_PURPOSE_D = 12; -const unsigned short AIC_GENERAL_PURPOSE_C = 13; -const unsigned short AIC_GENERAL_PURPOSE_B = 14; -const unsigned short AIC_GENERAL_PURPOSE_A = 15; - -//Analog output configuration -const unsigned short AOC_GENERAL_PURPOSE_A = 0; -const unsigned short AOC_GENERAL_PURPOSE_B = 1; + //Digital input configuration + const unsigned short DIC_NEGATIVE_LIMIT_SWITCH = 0; + const unsigned short DIC_POSITIVE_LIMIT_SWITCH = 1; + const unsigned short DIC_HOME_SWITCH = 2; + const unsigned short DIC_POSITION_MARKER = 3; + const unsigned short DIC_DRIVE_ENABLE = 4; + const unsigned short DIC_QUICK_STOP = 5; + const unsigned short DIC_GENERAL_PURPOSE_J = 6; + const unsigned short DIC_GENERAL_PURPOSE_I = 7; + const unsigned short DIC_GENERAL_PURPOSE_H = 8; + const unsigned short DIC_GENERAL_PURPOSE_G = 9; + const unsigned short DIC_GENERAL_PURPOSE_F = 10; + const unsigned short DIC_GENERAL_PURPOSE_E = 11; + const unsigned short DIC_GENERAL_PURPOSE_D = 12; + const unsigned short DIC_GENERAL_PURPOSE_C = 13; + const unsigned short DIC_GENERAL_PURPOSE_B = 14; + const unsigned short DIC_GENERAL_PURPOSE_A = 15; + + //Digital output configuration + const unsigned short DOC_READY_FAULT = 0; + const unsigned short DOC_POSITION_COMPARE = 1; + const unsigned short DOC_GENERAL_PURPOSE_H = 8; + const unsigned short DOC_GENERAL_PURPOSE_G = 9; + const unsigned short DOC_GENERAL_PURPOSE_F = 10; + const unsigned short DOC_GENERAL_PURPOSE_E = 11; + const unsigned short DOC_GENERAL_PURPOSE_D = 12; + const unsigned short DOC_GENERAL_PURPOSE_C = 13; + const unsigned short DOC_GENERAL_PURPOSE_B = 14; + const unsigned short DOC_GENERAL_PURPOSE_A = 15; + + //Analog input configuration + const unsigned short AIC_ANALOG_CURRENT_SETPOINT = 0; + const unsigned short AIC_ANALOG_VELOCITY_SETPOINT = 1; + const unsigned short AIC_ANALOG_POSITION_SETPOINT = 2; + const unsigned short AIC_GENERAL_PURPOSE_H = 8; + const unsigned short AIC_GENERAL_PURPOSE_G = 9; + const unsigned short AIC_GENERAL_PURPOSE_F = 10; + const unsigned short AIC_GENERAL_PURPOSE_E = 11; + const unsigned short AIC_GENERAL_PURPOSE_D = 12; + const unsigned short AIC_GENERAL_PURPOSE_C = 13; + const unsigned short AIC_GENERAL_PURPOSE_B = 14; + const unsigned short AIC_GENERAL_PURPOSE_A = 15; + + //Analog output configuration + const unsigned short AOC_GENERAL_PURPOSE_A = 0; + const unsigned short AOC_GENERAL_PURPOSE_B = 1; //Units -//VelocityDimension -const unsigned char VD_RPM = 0xA4; + //VelocityDimension + const unsigned char VD_RPM = 0xA4; -//VelocityNotation -const signed char VN_STANDARD = 0; -const signed char VN_DECI = -1; -const signed char VN_CENTI = -2; -const signed char VN_MILLI = -3; + //VelocityNotation + const signed char VN_STANDARD = 0; + const signed char VN_DECI = -1; + const signed char VN_CENTI = -2; + const signed char VN_MILLI = -3; //Operational mode -const signed char OMD_PROFILE_POSITION_MODE = 1; -const signed char OMD_PROFILE_VELOCITY_MODE = 3; -const signed char OMD_HOMING_MODE = 6; -const signed char OMD_INTERPOLATED_POSITION_MODE = 7; -const signed char OMD_POSITION_MODE = -1; -const signed char OMD_VELOCITY_MODE = -2; -const signed char OMD_CURRENT_MODE = -3; -const signed char OMD_MASTER_ENCODER_MODE = -5; -const signed char OMD_STEP_DIRECTION_MODE = -6; + const signed char OMD_PROFILE_POSITION_MODE = 1; + const signed char OMD_PROFILE_VELOCITY_MODE = 3; + const signed char OMD_HOMING_MODE = 6; + const signed char OMD_INTERPOLATED_POSITION_MODE = 7; + const signed char OMD_POSITION_MODE = -1; + const signed char OMD_VELOCITY_MODE = -2; + const signed char OMD_CURRENT_MODE = -3; + const signed char OMD_MASTER_ENCODER_MODE = -5; + const signed char OMD_STEP_DIRECTION_MODE = -6; //States -const unsigned short ST_DISABLED = 0; -const unsigned short ST_ENABLED = 1; -const unsigned short ST_QUICKSTOP = 2; -const unsigned short ST_FAULT = 3; + const unsigned short ST_DISABLED = 0; + const unsigned short ST_ENABLED = 1; + const unsigned short ST_QUICKSTOP = 2; + const unsigned short ST_FAULT = 3; //Homing mode -//Homing method -const char HM_ACTUAL_POSITION = 35; -const char HM_NEGATIVE_LIMIT_SWITCH = 17; -const char HM_NEGATIVE_LIMIT_SWITCH_AND_INDEX = 1; -const char HM_POSITIVE_LIMIT_SWITCH = 18; -const char HM_POSITIVE_LIMIT_SWITCH_AND_INDEX = 2; -const char HM_HOME_SWITCH_POSITIVE_SPEED = 23; -const char HM_HOME_SWITCH_POSITIVE_SPEED_AND_INDEX = 7; -const char HM_HOME_SWITCH_NEGATIVE_SPEED = 27; -const char HM_HOME_SWITCH_NEGATIVE_SPEED_AND_INDEX = 11; -const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED = -3; -const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED_AND_INDEX = -1; -const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED = -4; -const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED_AND_INDEX = -2; -const char HM_INDEX_POSITIVE_SPEED = 34; -const char HM_INDEX_NEGATIVE_SPEED = 33; + //Homing method + const char HM_ACTUAL_POSITION = 35; + const char HM_NEGATIVE_LIMIT_SWITCH = 17; + const char HM_NEGATIVE_LIMIT_SWITCH_AND_INDEX = 1; + const char HM_POSITIVE_LIMIT_SWITCH = 18; + const char HM_POSITIVE_LIMIT_SWITCH_AND_INDEX = 2; + const char HM_HOME_SWITCH_POSITIVE_SPEED = 23; + const char HM_HOME_SWITCH_POSITIVE_SPEED_AND_INDEX = 7; + const char HM_HOME_SWITCH_NEGATIVE_SPEED = 27; + const char HM_HOME_SWITCH_NEGATIVE_SPEED_AND_INDEX = 11; + const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED = -3; + const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED_AND_INDEX = -1; + const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED = -4; + const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED_AND_INDEX = -2; + const char HM_INDEX_POSITIVE_SPEED = 34; + const char HM_INDEX_NEGATIVE_SPEED = 33; //Input Output PositionMarker -//PositionMarkerEdgeType -const unsigned char PET_BOTH_EDGES = 0; -const unsigned char PET_RISING_EDGE = 1; -const unsigned char PET_FALLING_EDGE = 2; + //PositionMarkerEdgeType + const unsigned char PET_BOTH_EDGES = 0; + const unsigned char PET_RISING_EDGE = 1; + const unsigned char PET_FALLING_EDGE = 2; -//PositionMarkerMode -const unsigned char PM_CONTINUOUS = 0; -const unsigned char PM_SINGLE = 1; -const unsigned char PM_MULTIPLE = 2; + //PositionMarkerMode + const unsigned char PM_CONTINUOUS = 0; + const unsigned char PM_SINGLE = 1; + const unsigned char PM_MULTIPLE = 2; //Input Output PositionCompare -//PositionCompareOperationalMode -const unsigned char PCO_SINGLE_POSITION_MODE = 0; -const unsigned char PCO_POSITION_SEQUENCE_MODE = 1; + //PositionCompareOperationalMode + const unsigned char PCO_SINGLE_POSITION_MODE = 0; + const unsigned char PCO_POSITION_SEQUENCE_MODE = 1; -//PositionCompareIntervalMode -const unsigned char PCI_NEGATIVE_DIR_TO_REFPOS = 0; -const unsigned char PCI_POSITIVE_DIR_TO_REFPOS = 1; -const unsigned char PCI_BOTH_DIR_TO_REFPOS = 2; + //PositionCompareIntervalMode + const unsigned char PCI_NEGATIVE_DIR_TO_REFPOS = 0; + const unsigned char PCI_POSITIVE_DIR_TO_REFPOS = 1; + const unsigned char PCI_BOTH_DIR_TO_REFPOS = 2; -//PositionCompareDirectionDependency -const unsigned char PCD_MOTOR_DIRECTION_NEGATIVE = 0; -const unsigned char PCD_MOTOR_DIRECTION_POSITIVE = 1; -const unsigned char PCD_MOTOR_DIRECTION_BOTH = 2; + //PositionCompareDirectionDependency + const unsigned char PCD_MOTOR_DIRECTION_NEGATIVE = 0; + const unsigned char PCD_MOTOR_DIRECTION_POSITIVE = 1; + const unsigned char PCD_MOTOR_DIRECTION_BOTH = 2; //Data recorder -//Trigger type -const unsigned short DR_MOVEMENT_START_TRIGGER = 1; //bit 1 -const unsigned short DR_ERROR_TRIGGER = 2; //bit 2 -const unsigned short DR_DIGITAL_INPUT_TRIGGER = 4; //bit 3 -const unsigned short DR_MOVEMENT_END_TRIGGER = 8; //bit 4 + //Trigger type + const unsigned short DR_MOVEMENT_START_TRIGGER = 1; //bit 1 + const unsigned short DR_ERROR_TRIGGER = 2; //bit 2 + const unsigned short DR_DIGITAL_INPUT_TRIGGER = 4; //bit 3 + const unsigned short DR_MOVEMENT_END_TRIGGER = 8; //bit 4 //CanLayer Functions -const unsigned short NCS_START_REMOTE_NODE = 1; -const unsigned short NCS_STOP_REMOTE_NODE = 2; -const unsigned short NCS_ENTER_PRE_OPERATIONAL = 128; -const unsigned short NCS_RESET_NODE = 129; -const unsigned short NCS_RESET_COMMUNICATION = 130; + const unsigned short NCS_START_REMOTE_NODE = 1; + const unsigned short NCS_STOP_REMOTE_NODE = 2; + const unsigned short NCS_ENTER_PRE_OPERATIONAL = 128; + const unsigned short NCS_RESET_NODE = 129; + const unsigned short NCS_RESET_COMMUNICATION = 130; // Controller Gains -// EController -const unsigned short EC_PI_CURRENT_CONTROLLER = 1; -const unsigned short EC_PI_VELOCITY_CONTROLLER = 10; -const unsigned short EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER = 11; -const unsigned short EC_PID_POSITION_CONTROLLER = 20; -const unsigned short EC_DUAL_LOOP_POSITION_CONTROLLER = 21; - -// EGain (EC_PI_CURRENT_CONTROLLER) -const unsigned short EG_PICC_P_GAIN = 1; -const unsigned short EG_PICC_I_GAIN = 2; - -// EGain (EC_PI_VELOCITY_CONTROLLER) -const unsigned short EG_PIVC_P_GAIN = 1; -const unsigned short EG_PIVC_I_GAIN = 2; -const unsigned short EG_PIVC_FEED_FORWARD_VELOCITY_GAIN = 10; -const unsigned short EG_PIVC_FEED_FORWARD_ACCELERATION_GAIN = 11; - -// EGain (EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER) -const unsigned short EG_PIVCWO_P_GAIN = 1; -const unsigned short EG_PIVCWO_I_GAIN = 2; -const unsigned short EG_PIVCWO_FEED_FORWARD_VELOCITY_GAIN = 10; -const unsigned short EG_PIVCWO_FEED_FORWARD_ACCELERATION_GAIN = 11; -const unsigned short EG_PIVCWO_OBSERVER_THETA_GAIN = 20; -const unsigned short EG_PIVCWO_OBSERVER_OMEGA_GAIN = 21; -const unsigned short EG_PIVCWO_OBSERVER_TAU_GAIN = 22; - -// EGain (EC_PID_POSITION_CONTROLLER) -const unsigned short EG_PIDPC_P_GAIN = 1; -const unsigned short EG_PIDPC_I_GAIN = 2; -const unsigned short EG_PIDPC_D_GAIN = 3; -const unsigned short EG_PIDPC_FEED_FORWARD_VELOCITY_GAIN = 10; -const unsigned short EG_PIDPC_FEED_FORWARD_ACCELERATION_GAIN = 11; - -// EGain (EC_DUAL_LOOP_POSITION_CONTROLLER) -const unsigned short EG_DLPC_AUXILIARY_LOOP_P_GAIN = 1; -const unsigned short EG_DLPC_AUXILIARY_LOOP_I_GAIN = 2; -const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_VELOCITY_GAIN = 10; -const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_ACCELERATION_GAIN = 11; -const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_THETA_GAIN = 20; -const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_OMEGA_GAIN = 21; -const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_TAU_GAIN = 22; -const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_LOW = 101; -const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_HIGH = 102; -const unsigned short EG_DLPC_MAIN_LOOP_GAIN_SCHEDULING_WEIGHT = 110; -const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_A = 120; -const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_B = 121; -const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_C = 122; -const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_D = 123; -const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_E = 124; + // EController + const unsigned short EC_PI_CURRENT_CONTROLLER = 1; + const unsigned short EC_PI_VELOCITY_CONTROLLER = 10; + const unsigned short EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER = 11; + const unsigned short EC_PID_POSITION_CONTROLLER = 20; + const unsigned short EC_DUAL_LOOP_POSITION_CONTROLLER = 21; + + // EGain (EC_PI_CURRENT_CONTROLLER) + const unsigned short EG_PICC_P_GAIN = 1; + const unsigned short EG_PICC_I_GAIN = 2; + + // EGain (EC_PI_VELOCITY_CONTROLLER) + const unsigned short EG_PIVC_P_GAIN = 1; + const unsigned short EG_PIVC_I_GAIN = 2; + const unsigned short EG_PIVC_FEED_FORWARD_VELOCITY_GAIN = 10; + const unsigned short EG_PIVC_FEED_FORWARD_ACCELERATION_GAIN = 11; + + // EGain (EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER) + const unsigned short EG_PIVCWO_P_GAIN = 1; + const unsigned short EG_PIVCWO_I_GAIN = 2; + const unsigned short EG_PIVCWO_FEED_FORWARD_VELOCITY_GAIN = 10; + const unsigned short EG_PIVCWO_FEED_FORWARD_ACCELERATION_GAIN = 11; + const unsigned short EG_PIVCWO_OBSERVER_THETA_GAIN = 20; + const unsigned short EG_PIVCWO_OBSERVER_OMEGA_GAIN = 21; + const unsigned short EG_PIVCWO_OBSERVER_TAU_GAIN = 22; + + // EGain (EC_PID_POSITION_CONTROLLER) + const unsigned short EG_PIDPC_P_GAIN = 1; + const unsigned short EG_PIDPC_I_GAIN = 2; + const unsigned short EG_PIDPC_D_GAIN = 3; + const unsigned short EG_PIDPC_FEED_FORWARD_VELOCITY_GAIN = 10; + const unsigned short EG_PIDPC_FEED_FORWARD_ACCELERATION_GAIN = 11; + + // EGain (EC_DUAL_LOOP_POSITION_CONTROLLER) + const unsigned short EG_DLPC_AUXILIARY_LOOP_P_GAIN = 1; + const unsigned short EG_DLPC_AUXILIARY_LOOP_I_GAIN = 2; + const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_VELOCITY_GAIN = 10; + const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_ACCELERATION_GAIN = 11; + const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_THETA_GAIN = 20; + const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_OMEGA_GAIN = 21; + const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_TAU_GAIN = 22; + const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_LOW = 101; + const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_HIGH = 102; + const unsigned short EG_DLPC_MAIN_LOOP_GAIN_SCHEDULING_WEIGHT = 110; + const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_A = 120; + const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_B = 121; + const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_C = 122; + const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_D = 123; + const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_E = 124; #ifdef __cplusplus -} // extern "C" +} // export "C" #endif From 8fdd467137e8c4b3b7de173fd5cc75ca39f50435 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Wed, 18 Mar 2026 09:24:14 -0500 Subject: [PATCH 09/37] Just put it all into one src for now --- epos2/{ident.c => epos2.c} | 2 +- epos2/{ident.h => epos2.h} | 20 ++++++++++++++++++++ epos2/meson.build | 2 +- 3 files changed, 22 insertions(+), 2 deletions(-) rename epos2/{ident.c => epos2.c} (97%) rename epos2/{ident.h => epos2.h} (58%) diff --git a/epos2/ident.c b/epos2/epos2.c similarity index 97% rename from epos2/ident.c rename to epos2/epos2.c index 8430b73..97d8382 100644 --- a/epos2/ident.c +++ b/epos2/epos2.c @@ -2,7 +2,7 @@ #include #include "definitions.h" -#include "ident.h" +#include "epos2.h" int AcquireDeviceInformation(struct Controller* controller, int flags) { unsigned int error_code = 0; diff --git a/epos2/ident.h b/epos2/epos2.h similarity index 58% rename from epos2/ident.h rename to epos2/epos2.h index 8f11a7d..b0bbe61 100644 --- a/epos2/ident.h +++ b/epos2/epos2.h @@ -1,3 +1,8 @@ +/* + * a planning doc + * + */ + #pragma once #ifdef __cplusplus @@ -12,6 +17,16 @@ struct Controller { char Port[8]; }; +enum ACQUIRE_DEVICE_INFORMATION_FLAGS { + FLAG_INIT_DEFAULTS = 1, + FLAG_ZERO_INIT = 2 +}; + +/* + * Initializes the device and sets its state for a clean init. + */ +int InitializeDevice(); + /* * Populates the fields of the Controller information struct. * @@ -19,6 +34,11 @@ struct Controller { */ int AcquireDeviceInformation(struct Controller* controller, int flags); +/* + * Closes all connections to the controller + */ +int CloseDevice(struct Controller* controller); + #ifdef __cplusplus } // extern "C" } // namespace VSCL::Rig diff --git a/epos2/meson.build b/epos2/meson.build index 7f84116..b718bba 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -24,7 +24,7 @@ elif (operating_system == 'linux') required: false), ) - epos2_srcs = [ './epos2/constants.c', './epos2/ident.c' ] + epos2_srcs = [ './epos2/constants.c', './epos2/epos2.c' ] # Others else From 2c6238be12cbd124ccd98530b37a4192bdebc319 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Wed, 18 Mar 2026 10:07:48 -0500 Subject: [PATCH 10/37] Wrap around EPOS device init --- epos2/epos2.c | 38 +++++++++++++++++++++++++++++++------- epos2/epos2.h | 2 +- 2 files changed, 32 insertions(+), 8 deletions(-) diff --git a/epos2/epos2.c b/epos2/epos2.c index 97d8382..b5e8af8 100644 --- a/epos2/epos2.c +++ b/epos2/epos2.c @@ -1,26 +1,50 @@ #include +#include #include #include "definitions.h" #include "epos2.h" -int AcquireDeviceInformation(struct Controller* controller, int flags) { +int InitializeDevice(struct Controller* controller, void* device_handle) { + unsigned int error_code; + + unsigned int stacksets; + int ret; + + device_handle = (char*)VCS_OpenDevice(controller->Name, + controller->Protocol, + controller->Interface, + controller->Port, + &error_code); + + if (device_handle == 0 && error_code != 0) { + printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); + printf("- Name: %s\n", controller->Name); + printf("- Protocol: %s\n", controller->Protocol); + printf("- Interface: %s\n", controller->Interface); + printf("- Interface: %s\n", controller->Interface); + }; + + return error_code; +} + +int AcquireDeviceInformation(struct Controller* controller_out, int flags) { unsigned int error_code = 0; int success; int selection_end; - if (flags & (1 << 2)) { memset(controller, 0, sizeof(*controller)); } + if (flags & (1 << 2)) { memset(controller_out, 0, sizeof(*controller_out)); } if (flags & (1 << 1)) { - strncpy(controller->Name, "EPOS2", 6); - strncpy(controller->Protocol, "CANopen", 8); + strncpy(controller_out->Name, "EPOS2", 6); + strncpy(controller_out->Protocol, "CANopen", 8); } // TODO: will this behave expectedly? - // i.e only one connection to host pc means only one controller shows up? + // i.e only one connection to host pc means only one controller_out shows up? // or all three will show - success = VCS_GetInterfaceNameSelection(controller->Name, controller->Protocol, 1, - controller->Interface, 64, &selection_end, &error_code); + success = VCS_GetInterfaceNameSelection(controller_out->Name, controller_out->Protocol, 1, + controller_out->Interface, 64, &selection_end, &error_code); return (success == 0) ? 0 : error_code; } diff --git a/epos2/epos2.h b/epos2/epos2.h index b0bbe61..5c4c315 100644 --- a/epos2/epos2.h +++ b/epos2/epos2.h @@ -25,7 +25,7 @@ enum ACQUIRE_DEVICE_INFORMATION_FLAGS { /* * Initializes the device and sets its state for a clean init. */ -int InitializeDevice(); +int InitializeDevice(struct Controller* controller, void* device_handle); /* * Populates the fields of the Controller information struct. From 32e1f79a52b1fe1b73f1290b8c0157853dbc8177 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Wed, 18 Mar 2026 19:07:46 -0500 Subject: [PATCH 11/37] Don't forget the (non)portable pragma guard --- .github/workflows/build.yml | 1 + libtestrig_api.h | 2 ++ 2 files changed, 3 insertions(+) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 65b7320..63addd2 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -41,6 +41,7 @@ jobs: - name: Verbosely Test run: | meson test -v -C build + windows-build-meson: name: Windows runs-on: windows-latest diff --git a/libtestrig_api.h b/libtestrig_api.h index f3da688..c294eb7 100644 --- a/libtestrig_api.h +++ b/libtestrig_api.h @@ -1,3 +1,5 @@ +#pragma once + #ifndef TESTRIG_API #if defined(_WIN32) && !defined(__GNUC__) #ifdef COMPILING_TESTRIG_DLL From e3bc459e253eb0814aa3ac964f157ab4f7532243 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Wed, 18 Mar 2026 19:20:41 -0500 Subject: [PATCH 12/37] More fixups on meson.builds --- epos2/meson.build | 2 +- ipc/meson.build | 11 +---------- meson.build | 8 ++++---- test/meson.build | 4 +--- 4 files changed, 7 insertions(+), 18 deletions(-) diff --git a/epos2/meson.build b/epos2/meson.build index b718bba..73a034d 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -33,7 +33,7 @@ endif # CI etc. else - message('[WARNING] Controller capabilities not being built. Continuing to create library anyway') + message('[WARNING] Controller capabilities not being built. Continuing to create library anyway.') epos2 = declare_dependency() epos2_srcs = [ ] endif diff --git a/ipc/meson.build b/ipc/meson.build index 39871de..0dddf79 100644 --- a/ipc/meson.build +++ b/ipc/meson.build @@ -1,12 +1,3 @@ -# RM ME WHEN EPOS2 is merged -## Machine info -operating_system = host_machine.system() -cpu_architecture = host_machine.cpu_family() -valid_os = ['windows', 'linux'] -valid_arch = ['x86', 'x86_64', 'aarch64', 'arm'] - -# END RM - if (operating_system.to_lower() == 'windows') ipc_os_deps = declare_dependency( dependencies: cc.find_library('Ws2_32', @@ -16,4 +7,4 @@ elif (operating_system.to_lower() == 'linux') ipc_os_deps = declare_dependency() else error('Unsupported operating system or build environment: ' + operating_system) -endif \ No newline at end of file +endif diff --git a/meson.build b/meson.build index 5925fa0..e86224e 100644 --- a/meson.build +++ b/meson.build @@ -9,14 +9,14 @@ cpu_architecture = host_machine.cpu_family() valid_os = ['windows', 'linux'] valid_arch = ['x86', 'x86_64', 'aarch64', 'arm'] -subdir('ipc') - ## Main Binary Definitions +subdir('ipc') subdir('epos2') srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c', 'ipc/os.c' ] + epos2_srcs -lib = shared_library('testrig', srcs, dependencies: ipc_os_deps, c_args: ['-DCOMPILING_TESTRIG_DLL'], dependencies: epos2 ) +lib = shared_library('testrig', srcs, + dependencies: [ ipc_os_deps, epos2 ], c_args: ['-DCOMPILING_TESTRIG_DLL'] ) dep = declare_dependency(include_directories: '.', link_with: lib, dependencies: epos2) -subdir('test') \ No newline at end of file +subdir('test') diff --git a/test/meson.build b/test/meson.build index 01bc379..6a33a4f 100644 --- a/test/meson.build +++ b/test/meson.build @@ -14,8 +14,6 @@ elif (operating_system.to_lower() == 'windows') dependencies: cc.find_library('Kernel32', required: true), ) - -message(meson.project_source_root() / 'build') dllcopy = [find_program('python'), meson.project_source_root() / 'test' / 'copy_dlls.meson.py', @@ -33,4 +31,4 @@ message(meson.project_source_root() / 'build') test('discrete', mgr_exe, args: [ server_exe.full_path(), client_exe.full_path() ], depends: [ client_exe, server_exe, move_dlls_py ]) -endif \ No newline at end of file +endif From f549b83bf065b3d240c855248807b531d20f74d3 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Wed, 18 Mar 2026 19:37:46 -0500 Subject: [PATCH 13/37] minimal implements of devve ident + comms opens/closes --- epos2/epos2.c | 24 +++++++++++++++++------- epos2/epos2.h | 8 +++++--- 2 files changed, 22 insertions(+), 10 deletions(-) diff --git a/epos2/epos2.c b/epos2/epos2.c index b5e8af8..1725f31 100644 --- a/epos2/epos2.c +++ b/epos2/epos2.c @@ -5,13 +5,11 @@ #include "definitions.h" #include "epos2.h" -int InitializeDevice(struct Controller* controller, void* device_handle) { +unsigned int InitializeDevice(struct Controller* controller, void* device_handle) { unsigned int error_code; - - unsigned int stacksets; int ret; - device_handle = (char*)VCS_OpenDevice(controller->Name, + device_handle = VCS_OpenDevice(controller->Name, controller->Protocol, controller->Interface, controller->Port, @@ -23,12 +21,15 @@ int InitializeDevice(struct Controller* controller, void* device_handle) { printf("- Protocol: %s\n", controller->Protocol); printf("- Interface: %s\n", controller->Interface); printf("- Interface: %s\n", controller->Interface); + return error_code; }; - return error_code; + ret = VCS_ClearFault(device_handle, 0, &error_code); + + return (ret == 0 && error_code == 0) ? 0 : error_code; } -int AcquireDeviceInformation(struct Controller* controller_out, int flags) { +unsigned int AcquireDeviceInformation(struct Controller* controller_out, int flags) { unsigned int error_code = 0; int success; int selection_end; @@ -46,5 +47,14 @@ int AcquireDeviceInformation(struct Controller* controller_out, int flags) { success = VCS_GetInterfaceNameSelection(controller_out->Name, controller_out->Protocol, 1, controller_out->Interface, 64, &selection_end, &error_code); - return (success == 0) ? 0 : error_code; + return (success == 0 && error_code == 0) ? 0 : error_code; +} + +unsigned int CloseDevice(struct Controller* controller, void* device_handle) { + unsigned int error_code; + int ret; + + ret = VCS_CloseDevice(device_handle, &error_code); + + return (ret == 0 && error_code == 0) ? 0 : error_code; } diff --git a/epos2/epos2.h b/epos2/epos2.h index 5c4c315..ef4c0ac 100644 --- a/epos2/epos2.h +++ b/epos2/epos2.h @@ -24,20 +24,22 @@ enum ACQUIRE_DEVICE_INFORMATION_FLAGS { /* * Initializes the device and sets its state for a clean init. + * + * Refer to Page 162 of the manual. */ -int InitializeDevice(struct Controller* controller, void* device_handle); +unsigned int InitializeDevice(struct Controller* controller, void* device_handle); /* * Populates the fields of the Controller information struct. * * Flags are passed bitwise ORed. */ -int AcquireDeviceInformation(struct Controller* controller, int flags); +unsigned int AcquireDeviceInformation(struct Controller* controller, int flags); /* * Closes all connections to the controller */ -int CloseDevice(struct Controller* controller); +unsigned int CloseDevice(struct Controller* controller, void* device_handle); #ifdef __cplusplus } // extern "C" From bffbb9f503d011802f7dbcee60c9d9ec4b74d16e Mon Sep 17 00:00:00 2001 From: JC Luna Date: Wed, 18 Mar 2026 21:08:30 -0500 Subject: [PATCH 14/37] Controller identity printer --- epos2/epos2.c | 21 +++++++++++---------- epos2/epos2.h | 32 ++++++++++++++++++++------------ 2 files changed, 31 insertions(+), 22 deletions(-) diff --git a/epos2/epos2.c b/epos2/epos2.c index 1725f31..bdb4e70 100644 --- a/epos2/epos2.c +++ b/epos2/epos2.c @@ -1,4 +1,3 @@ -#include #include #include @@ -17,14 +16,10 @@ unsigned int InitializeDevice(struct Controller* controller, void* device_handle if (device_handle == 0 && error_code != 0) { printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); - printf("- Name: %s\n", controller->Name); - printf("- Protocol: %s\n", controller->Protocol); - printf("- Interface: %s\n", controller->Interface); - printf("- Interface: %s\n", controller->Interface); return error_code; }; - ret = VCS_ClearFault(device_handle, 0, &error_code); + ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); return (ret == 0 && error_code == 0) ? 0 : error_code; } @@ -41,10 +36,8 @@ unsigned int AcquireDeviceInformation(struct Controller* controller_out, int fla strncpy(controller_out->Protocol, "CANopen", 8); } - // TODO: will this behave expectedly? - // i.e only one connection to host pc means only one controller_out shows up? - // or all three will show - success = VCS_GetInterfaceNameSelection(controller_out->Name, controller_out->Protocol, 1, + success = VCS_GetInterfaceNameSelection( + controller_out->Name, controller_out->Protocol, 1, controller_out->Interface, 64, &selection_end, &error_code); return (success == 0 && error_code == 0) ? 0 : error_code; @@ -58,3 +51,11 @@ unsigned int CloseDevice(struct Controller* controller, void* device_handle) { return (ret == 0 && error_code == 0) ? 0 : error_code; } + +void PrintControllerCharacteristics(struct Controller* controller) { + printf("- Name: %s\n", controller->Name); + printf("- Node: %i\n", controller->NodeId); + printf("- Protocol: %s\n", controller->Protocol); + printf("- Interface: %s\n", controller->Interface); + printf("- Interface: %s\n", controller->Interface); +} diff --git a/epos2/epos2.h b/epos2/epos2.h index ef4c0ac..ea01b16 100644 --- a/epos2/epos2.h +++ b/epos2/epos2.h @@ -1,8 +1,3 @@ -/* - * a planning doc - * - */ - #pragma once #ifdef __cplusplus @@ -10,11 +5,14 @@ namespace VSCL::Rig { extern "C" { #endif // __cplusplus +#include "libtestrig_api.h" + struct Controller { char Name[8]; char Protocol[16]; char Interface[64]; char Port[8]; + unsigned short NodeId; }; enum ACQUIRE_DEVICE_INFORMATION_FLAGS { @@ -23,23 +21,33 @@ enum ACQUIRE_DEVICE_INFORMATION_FLAGS { }; /* - * Initializes the device and sets its state for a clean init. + * Populates the fields of the Controller information struct. * - * Refer to Page 162 of the manual. + * Flags are passed bitwise ORed. */ -unsigned int InitializeDevice(struct Controller* controller, void* device_handle); +unsigned int TESTRIG_API AcquireDeviceInformation(struct Controller* controller, int flags); /* - * Populates the fields of the Controller information struct. * - * Flags are passed bitwise ORed. */ -unsigned int AcquireDeviceInformation(struct Controller* controller, int flags); +unsigned int TESTRIG_API AcquireThreeDeviceInformations(struct Controller* controller, int flags); + +/* + * Initializes the device and sets its state for a clean init. + * + * Refer to Page 162 of the manual. + */ +unsigned int TESTRIG_API InitializeDevice(struct Controller* controller, void* device_handle); /* * Closes all connections to the controller */ -unsigned int CloseDevice(struct Controller* controller, void* device_handle); +unsigned int TESTRIG_API CloseDevice(struct Controller* controller, void* device_handle); + +/* + * Print out controller characteristics. + */ +void TESTRIG_API PrintControllerCharacteristics(struct Controller* controller); #ifdef __cplusplus } // extern "C" From 18a28232449d56e6f194fc065c39c46f2e652e88 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Thu, 19 Mar 2026 17:55:18 -0500 Subject: [PATCH 15/37] EPOS Sources reorganized --- epos2/connect.c | 35 ++ epos2/connect.h | 30 ++ epos2/constants.c | 1 - epos2/constants.h | 23 -- epos2/controller.h | 41 +++ epos2/definitions.c | 215 +++++++++++ epos2/definitions.h | 848 ++++++++++++++++++++++---------------------- epos2/epos2.c | 60 +--- epos2/epos2.h | 49 +-- epos2/identify.c | 32 ++ epos2/identify.h | 35 ++ epos2/meson.build | 3 +- 12 files changed, 821 insertions(+), 551 deletions(-) create mode 100644 epos2/connect.c create mode 100644 epos2/connect.h delete mode 100644 epos2/constants.c delete mode 100644 epos2/constants.h create mode 100644 epos2/controller.h create mode 100644 epos2/definitions.c create mode 100644 epos2/identify.c create mode 100644 epos2/identify.h diff --git a/epos2/connect.c b/epos2/connect.c new file mode 100644 index 0000000..fd2ed18 --- /dev/null +++ b/epos2/connect.c @@ -0,0 +1,35 @@ +#include + +#include "definitions.h" +#include "connect.h" + +unsigned int InitializeDevice(struct Controller* controller, void* device_handle) { + unsigned int error_code; + int ret; + + device_handle = VCS_OpenDevice(controller->Name, + controller->Protocol, + controller->Interface, + controller->Port, + &error_code); + + if (device_handle == 0 && error_code != 0) { + printf("ERROR %uix: Failed to open device with with following characteristics:\n", + error_code); + return error_code; + }; + + ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); + + return (ret == 0 && error_code == 0) ? 0 : error_code; +} // uint Open + +unsigned int CloseDevice(struct Controller* controller, void* device_handle) { + unsigned int error_code; + int ret; + + ret = VCS_CloseDevice(device_handle, &error_code); + + return (ret == 0 && error_code == 0) ? 0 : error_code; +} + diff --git a/epos2/connect.h b/epos2/connect.h new file mode 100644 index 0000000..21da9e7 --- /dev/null +++ b/epos2/connect.h @@ -0,0 +1,30 @@ +#pragma once + +#ifdef __cplusplus +namespace VSCL::Rig { +extern "C" { +#endif // __cplusplus + +#include "libtestrig_api.h" +#include "controller.h" + +/* + * @brief Opens communication to the device and sets its state for a clean init. + * + * Refer to Page 162 of the manual under INITIALIZATION, + * which describes several of the methods wrapped here. + */ +unsigned int TESTRIG_API InitializeDevice(struct Controller* controller, void* device_handle); + +/* + * Closes all connections to the controller + * + * Refer to Page 162 of the manual under CLOSING PROCEDURE, + * which describes several of the methods wrapped here. + */ +unsigned int TESTRIG_API CloseDevice(struct Controller* controller, void* device_handle); + +#ifdef __cplusplus +} // extern "C" +} // namespace VSCL::Rig +#endif // __cplusplus diff --git a/epos2/constants.c b/epos2/constants.c deleted file mode 100644 index 04a2aa6..0000000 --- a/epos2/constants.c +++ /dev/null @@ -1 +0,0 @@ -#include "constants.h" diff --git a/epos2/constants.h b/epos2/constants.h deleted file mode 100644 index 2aceaeb..0000000 --- a/epos2/constants.h +++ /dev/null @@ -1,23 +0,0 @@ -#pragma once - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#ifdef __cplusplus -} -namespace VSCL::Rig { -extern "C" { -#endif // __cplusplus - -enum ACQUIRE_DEVICE_INFORMATION_FLAGS { - FLAG_INIT_DEFAULTS = 1, - FLAG_ZERO_INIT = 2 -}; - -#ifdef __cplusplus -} // extern "C" -} // namespace VSCL::Rig -#endif // __cplusplus diff --git a/epos2/controller.h b/epos2/controller.h new file mode 100644 index 0000000..2872b72 --- /dev/null +++ b/epos2/controller.h @@ -0,0 +1,41 @@ +#pragma once + +#ifdef __cplusplus +namespace VSCL::Rig { +extern "C" { +#endif // __cplusplus + +enum ACQUIRE_DEVICE_INFORMATION_FLAGS { + FLAG_INIT_DEFAULTS = 1, + FLAG_ZERO_INIT = 2 +}; + +enum ControllerState { + CTRL_STATE_CLOSED = 1, + CTRL_STATE_OPENED = 2, +}; + +/* + * @brief A struct representing a controller. + * + * Refer to the parameters passed to VCS_OpenDevice, Page 13 of the Manual. + */ +struct Controller { + // The name of the controller. + char Name[8]; + // The name of the communication protocol. + char Protocol[16]; + // The name of the connection interface. + char Interface[64]; + // The name of the port used in connection. + char Port[8]; + // The node of the controller. + unsigned short NodeId; + // State of the controller. + enum ControllerState State; +}; + +#ifdef __cplusplus +} // extern "C" +} // namespace VSCL::Rig +#endif // __cplusplus diff --git a/epos2/definitions.c b/epos2/definitions.c new file mode 100644 index 0000000..b7e0049 --- /dev/null +++ b/epos2/definitions.c @@ -0,0 +1,215 @@ +// ******************************************************************************************************************* +// maxon motor ag, CH-6072 Sachseln +// ******************************************************************************************************************* +// Copyright © 2003 - 2021, maxon motor ag. +// All rights reserved. +// ******************************************************************************************************************* + +#include "definitions.h" + +const int DM_PROGRESS_DLG = 0; +const int DM_PROGRESS_AND_CONFIRM_DLG = 1; +const int DM_CONFIRM_DLG = 2; +const int DM_NO_DLG = 3; + +//Configuration +//MotorType +const unsigned short MT_DC_MOTOR = 1; +const unsigned short MT_EC_SINUS_COMMUTATED_MOTOR = 10; +const unsigned short MT_EC_BLOCK_COMMUTATED_MOTOR = 11; + +//SensorType +const unsigned short ST_UNKNOWN = 0; +const unsigned short ST_INC_ENCODER_3CHANNEL = 1; +const unsigned short ST_INC_ENCODER_2CHANNEL = 2; +const unsigned short ST_HALL_SENSORS = 3; +const unsigned short ST_SSI_ABS_ENCODER_BINARY = 4; +const unsigned short ST_SSI_ABS_ENCODER_GREY = 5; +const unsigned short ST_INC_ENCODER2_3CHANNEL = 6; +const unsigned short ST_INC_ENCODER2_2CHANNEL = 7; +const unsigned short ST_ANALOG_INC_ENCODER_3CHANNEL = 8; +const unsigned short ST_ANALOG_INC_ENCODER_2CHANNEL = 9; + +//In- and outputs +//Digital input configuration +const unsigned short DIC_NEGATIVE_LIMIT_SWITCH = 0; +const unsigned short DIC_POSITIVE_LIMIT_SWITCH = 1; +const unsigned short DIC_HOME_SWITCH = 2; +const unsigned short DIC_POSITION_MARKER = 3; +const unsigned short DIC_DRIVE_ENABLE = 4; +const unsigned short DIC_QUICK_STOP = 5; +const unsigned short DIC_GENERAL_PURPOSE_J = 6; +const unsigned short DIC_GENERAL_PURPOSE_I = 7; +const unsigned short DIC_GENERAL_PURPOSE_H = 8; +const unsigned short DIC_GENERAL_PURPOSE_G = 9; +const unsigned short DIC_GENERAL_PURPOSE_F = 10; +const unsigned short DIC_GENERAL_PURPOSE_E = 11; +const unsigned short DIC_GENERAL_PURPOSE_D = 12; +const unsigned short DIC_GENERAL_PURPOSE_C = 13; +const unsigned short DIC_GENERAL_PURPOSE_B = 14; +const unsigned short DIC_GENERAL_PURPOSE_A = 15; + +//Digital output configuration +const unsigned short DOC_READY_FAULT = 0; +const unsigned short DOC_POSITION_COMPARE = 1; +const unsigned short DOC_GENERAL_PURPOSE_H = 8; +const unsigned short DOC_GENERAL_PURPOSE_G = 9; +const unsigned short DOC_GENERAL_PURPOSE_F = 10; +const unsigned short DOC_GENERAL_PURPOSE_E = 11; +const unsigned short DOC_GENERAL_PURPOSE_D = 12; +const unsigned short DOC_GENERAL_PURPOSE_C = 13; +const unsigned short DOC_GENERAL_PURPOSE_B = 14; +const unsigned short DOC_GENERAL_PURPOSE_A = 15; + +//Analog input configuration +const unsigned short AIC_ANALOG_CURRENT_SETPOINT = 0; +const unsigned short AIC_ANALOG_VELOCITY_SETPOINT = 1; +const unsigned short AIC_ANALOG_POSITION_SETPOINT = 2; +const unsigned short AIC_GENERAL_PURPOSE_H = 8; +const unsigned short AIC_GENERAL_PURPOSE_G = 9; +const unsigned short AIC_GENERAL_PURPOSE_F = 10; +const unsigned short AIC_GENERAL_PURPOSE_E = 11; +const unsigned short AIC_GENERAL_PURPOSE_D = 12; +const unsigned short AIC_GENERAL_PURPOSE_C = 13; +const unsigned short AIC_GENERAL_PURPOSE_B = 14; +const unsigned short AIC_GENERAL_PURPOSE_A = 15; + +//Analog output configuration +const unsigned short AOC_GENERAL_PURPOSE_A = 0; +const unsigned short AOC_GENERAL_PURPOSE_B = 1; + +//Units +//VelocityDimension +const unsigned char VD_RPM = 0xA4; + +//VelocityNotation +const signed char VN_STANDARD = 0; +const signed char VN_DECI = -1; +const signed char VN_CENTI = -2; +const signed char VN_MILLI = -3; + +//Operational mode +const signed char OMD_PROFILE_POSITION_MODE = 1; +const signed char OMD_PROFILE_VELOCITY_MODE = 3; +const signed char OMD_HOMING_MODE = 6; +const signed char OMD_INTERPOLATED_POSITION_MODE = 7; +const signed char OMD_POSITION_MODE = -1; +const signed char OMD_VELOCITY_MODE = -2; +const signed char OMD_CURRENT_MODE = -3; +const signed char OMD_MASTER_ENCODER_MODE = -5; +const signed char OMD_STEP_DIRECTION_MODE = -6; + +//States +const unsigned short ST_DISABLED = 0; +const unsigned short ST_ENABLED = 1; +const unsigned short ST_QUICKSTOP = 2; +const unsigned short ST_FAULT = 3; + +//Homing mode +//Homing method +const char HM_ACTUAL_POSITION = 35; +const char HM_NEGATIVE_LIMIT_SWITCH = 17; +const char HM_NEGATIVE_LIMIT_SWITCH_AND_INDEX = 1; +const char HM_POSITIVE_LIMIT_SWITCH = 18; +const char HM_POSITIVE_LIMIT_SWITCH_AND_INDEX = 2; +const char HM_HOME_SWITCH_POSITIVE_SPEED = 23; +const char HM_HOME_SWITCH_POSITIVE_SPEED_AND_INDEX = 7; +const char HM_HOME_SWITCH_NEGATIVE_SPEED = 27; +const char HM_HOME_SWITCH_NEGATIVE_SPEED_AND_INDEX = 11; +const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED = -3; +const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED_AND_INDEX = -1; +const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED = -4; +const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED_AND_INDEX = -2; +const char HM_INDEX_POSITIVE_SPEED = 34; +const char HM_INDEX_NEGATIVE_SPEED = 33; + +//Input Output PositionMarker +//PositionMarkerEdgeType +const unsigned char PET_BOTH_EDGES = 0; +const unsigned char PET_RISING_EDGE = 1; +const unsigned char PET_FALLING_EDGE = 2; + +//PositionMarkerMode +const unsigned char PM_CONTINUOUS = 0; +const unsigned char PM_SINGLE = 1; +const unsigned char PM_MULTIPLE = 2; + +//Input Output PositionCompare +//PositionCompareOperationalMode +const unsigned char PCO_SINGLE_POSITION_MODE = 0; +const unsigned char PCO_POSITION_SEQUENCE_MODE = 1; + +//PositionCompareIntervalMode +const unsigned char PCI_NEGATIVE_DIR_TO_REFPOS = 0; +const unsigned char PCI_POSITIVE_DIR_TO_REFPOS = 1; +const unsigned char PCI_BOTH_DIR_TO_REFPOS = 2; + +//PositionCompareDirectionDependency +const unsigned char PCD_MOTOR_DIRECTION_NEGATIVE = 0; +const unsigned char PCD_MOTOR_DIRECTION_POSITIVE = 1; +const unsigned char PCD_MOTOR_DIRECTION_BOTH = 2; + +//Data recorder +//Trigger type +const unsigned short DR_MOVEMENT_START_TRIGGER = 1; //bit 1 +const unsigned short DR_ERROR_TRIGGER = 2; //bit 2 +const unsigned short DR_DIGITAL_INPUT_TRIGGER = 4; //bit 3 +const unsigned short DR_MOVEMENT_END_TRIGGER = 8; //bit 4 + +//CanLayer Functions +const unsigned short NCS_START_REMOTE_NODE = 1; +const unsigned short NCS_STOP_REMOTE_NODE = 2; +const unsigned short NCS_ENTER_PRE_OPERATIONAL = 128; +const unsigned short NCS_RESET_NODE = 129; +const unsigned short NCS_RESET_COMMUNICATION = 130; + +// Controller Gains +// EController +const unsigned short EC_PI_CURRENT_CONTROLLER = 1; +const unsigned short EC_PI_VELOCITY_CONTROLLER = 10; +const unsigned short EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER = 11; +const unsigned short EC_PID_POSITION_CONTROLLER = 20; +const unsigned short EC_DUAL_LOOP_POSITION_CONTROLLER = 21; + +// EGain (EC_PI_CURRENT_CONTROLLER) +const unsigned short EG_PICC_P_GAIN = 1; +const unsigned short EG_PICC_I_GAIN = 2; + +// EGain (EC_PI_VELOCITY_CONTROLLER) +const unsigned short EG_PIVC_P_GAIN = 1; +const unsigned short EG_PIVC_I_GAIN = 2; +const unsigned short EG_PIVC_FEED_FORWARD_VELOCITY_GAIN = 10; +const unsigned short EG_PIVC_FEED_FORWARD_ACCELERATION_GAIN = 11; + +// EGain (EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER) +const unsigned short EG_PIVCWO_P_GAIN = 1; +const unsigned short EG_PIVCWO_I_GAIN = 2; +const unsigned short EG_PIVCWO_FEED_FORWARD_VELOCITY_GAIN = 10; +const unsigned short EG_PIVCWO_FEED_FORWARD_ACCELERATION_GAIN = 11; +const unsigned short EG_PIVCWO_OBSERVER_THETA_GAIN = 20; +const unsigned short EG_PIVCWO_OBSERVER_OMEGA_GAIN = 21; +const unsigned short EG_PIVCWO_OBSERVER_TAU_GAIN = 22; + +// EGain (EC_PID_POSITION_CONTROLLER) +const unsigned short EG_PIDPC_P_GAIN = 1; +const unsigned short EG_PIDPC_I_GAIN = 2; +const unsigned short EG_PIDPC_D_GAIN = 3; +const unsigned short EG_PIDPC_FEED_FORWARD_VELOCITY_GAIN = 10; +const unsigned short EG_PIDPC_FEED_FORWARD_ACCELERATION_GAIN = 11; + +// EGain (EC_DUAL_LOOP_POSITION_CONTROLLER) +const unsigned short EG_DLPC_AUXILIARY_LOOP_P_GAIN = 1; +const unsigned short EG_DLPC_AUXILIARY_LOOP_I_GAIN = 2; +const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_VELOCITY_GAIN = 10; +const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_ACCELERATION_GAIN = 11; +const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_THETA_GAIN = 20; +const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_OMEGA_GAIN = 21; +const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_TAU_GAIN = 22; +const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_LOW = 101; +const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_HIGH = 102; +const unsigned short EG_DLPC_MAIN_LOOP_GAIN_SCHEDULING_WEIGHT = 110; +const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_A = 120; +const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_B = 121; +const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_C = 122; +const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_D = 123; +const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_E = 124; diff --git a/epos2/definitions.h b/epos2/definitions.h index c49704a..c302192 100644 --- a/epos2/definitions.h +++ b/epos2/definitions.h @@ -56,530 +56,530 @@ extern "C" { #endif -//Communication -int CreateCommunication(); -int DeleteCommunication(); - -// Data Recorder -int CreateDataRecorderCmdManager(void* KeyHandle); -int DeleteDataRecorderCmdManager(); +////Communication +//int CreateCommunication(); +//int DeleteCommunication(); +// +//// Data Recorder +//int CreateDataRecorderCmdManager(void* KeyHandle); +//int DeleteDataRecorderCmdManager(); /************************************************************************************************************************************* * INITIALISATION FUNCTIONS *************************************************************************************************************************************/ //Communication - Initialisation_DllExport void* VCS_OpenDevice(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, unsigned int* pErrorCode); - Initialisation_DllExport int VCS_SetProtocolStackSettings(void* KeyHandle, unsigned int Baudrate, unsigned int Timeout, unsigned int* pErrorCode); - Initialisation_DllExport int VCS_GetProtocolStackSettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pTimeout, unsigned int* pErrorCode); - Initialisation_DllExport int VCS_CloseDevice(void* KeyHandle, unsigned int* pErrorCode); - Initialisation_DllExport int VCS_CloseAllDevices(unsigned int* pErrorCode); +Initialisation_DllExport void* VCS_OpenDevice(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_SetProtocolStackSettings(void* KeyHandle, unsigned int Baudrate, unsigned int Timeout, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_GetProtocolStackSettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pTimeout, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_CloseDevice(void* KeyHandle, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_CloseAllDevices(unsigned int* pErrorCode); //Gateway - Initialisation_DllExport int VCS_SetGatewaySettings(void* KeyHandle, unsigned int Baudrate, unsigned int* pErrorCode); - Initialisation_DllExport int VCS_GetGatewaySettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_SetGatewaySettings(void* KeyHandle, unsigned int Baudrate, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_GetGatewaySettings(void* KeyHandle, unsigned int* pBaudrate, unsigned int* pErrorCode); //Sub device - Initialisation_DllExport void* VCS_OpenSubDevice(void* DeviceHandle, char* DeviceName, char* ProtocolStackName, unsigned int* pErrorCode); - Initialisation_DllExport int VCS_CloseSubDevice(void* KeyHandle, unsigned int* pErrorCode); - Initialisation_DllExport int VCS_CloseAllSubDevices(void* DeviceHandle, unsigned int* pErrorCode); +Initialisation_DllExport void* VCS_OpenSubDevice(void* DeviceHandle, char* DeviceName, char* ProtocolStackName, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_CloseSubDevice(void* KeyHandle, unsigned int* pErrorCode); +Initialisation_DllExport int VCS_CloseAllSubDevices(void* DeviceHandle, unsigned int* pErrorCode); //Info - HelpFunctions_DllExport int VCS_GetDriverInfo(char* p_pszLibraryName, unsigned short p_usMaxLibraryNameStrSize,char* p_pszLibraryVersion, unsigned short p_usMaxLibraryVersionStrSize, unsigned int* p_pErrorCode); - 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); - HelpFunctions_DllExport int VCS_GetErrorInfo(unsigned int ErrorCodeValue, char* pErrorInfo, unsigned short MaxStrSize); +HelpFunctions_DllExport int VCS_GetDriverInfo(char* p_pszLibraryName, unsigned short p_usMaxLibraryNameStrSize,char* p_pszLibraryVersion, unsigned short p_usMaxLibraryVersionStrSize, unsigned int* p_pErrorCode); +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); +HelpFunctions_DllExport int VCS_GetErrorInfo(unsigned int ErrorCodeValue, char* pErrorInfo, unsigned short MaxStrSize); //Advanced Functions - HelpFunctions_DllExport int VCS_GetDeviceNameSelection(int StartOfSelection, char* pDeviceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetProtocolStackNameSelection(char* DeviceName, int StartOfSelection, char* pProtocolStackNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetInterfaceNameSelection(char* DeviceName, char* ProtocolStackName, int StartOfSelection, char* pInterfaceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, int StartOfSelection, char* pPortSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_ResetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetBaudrateSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, int StartOfSelection, unsigned int* pBaudrateSel, int* pEndOfSelection, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetKeyHandle(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, void** pKeyHandle, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetDeviceName(void* KeyHandle, char* pDeviceName, unsigned short MaxStrSize, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetProtocolStackName(void* KeyHandle, char* pProtocolStackName, unsigned short MaxStrSize, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetInterfaceName(void* KeyHandle, char* pInterfaceName, unsigned short MaxStrSize, unsigned int* pErrorCode); - HelpFunctions_DllExport int VCS_GetPortName(void* KeyHandle, char* pPortName, unsigned short MaxStrSize, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetDeviceNameSelection(int StartOfSelection, char* pDeviceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetProtocolStackNameSelection(char* DeviceName, int StartOfSelection, char* pProtocolStackNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetInterfaceNameSelection(char* DeviceName, char* ProtocolStackName, int StartOfSelection, char* pInterfaceNameSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, int StartOfSelection, char* pPortSel, unsigned short MaxStrSize, int* pEndOfSelection, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_ResetPortNameSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetBaudrateSelection(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, int StartOfSelection, unsigned int* pBaudrateSel, int* pEndOfSelection, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetKeyHandle(char* DeviceName, char* ProtocolStackName, char* InterfaceName, char* PortName, void** pKeyHandle, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetDeviceName(void* KeyHandle, char* pDeviceName, unsigned short MaxStrSize, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetProtocolStackName(void* KeyHandle, char* pProtocolStackName, unsigned short MaxStrSize, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetInterfaceName(void* KeyHandle, char* pInterfaceName, unsigned short MaxStrSize, unsigned int* pErrorCode); +HelpFunctions_DllExport int VCS_GetPortName(void* KeyHandle, char* pPortName, unsigned short MaxStrSize, unsigned int* pErrorCode); /************************************************************************************************************************************* * CONFIGURATION FUNCTIONS *************************************************************************************************************************************/ //General - 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); - 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); - Configuration_DllExport int VCS_Restore(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - Configuration_DllExport int VCS_Store(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +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); +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); +Configuration_DllExport int VCS_Restore(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +Configuration_DllExport int VCS_Store(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Advanced Functions - //Motor - Configuration_DllExport int VCS_SetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short MotorType, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short NominalCurrent, unsigned short MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); - 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); - Configuration_DllExport int VCS_SetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned char NbOfPolePairs, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short* pMotorType, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pNominalCurrent, unsigned short* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); - 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); - Configuration_DllExport int VCS_GetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned char* pNbOfPolePairs, unsigned int* pErrorCode); - - //Sensor - Configuration_DllExport int VCS_SetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short SensorType, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int EncoderResolution, int InvertedPolarity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int InvertedPolarity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, int InvertedPolarity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSpecialDataBits, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfSpecialDataBitsLeading, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfMultiTurnPositionBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSingleTurnPositionBits, unsigned short NbOfSpecialDataBitsTrailing, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, int CheckFrame, int ReferenceReset, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short* pSensorType, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pEncoderResolution, int* pInvertedPolarity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int* pInvertedPolarity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, int* pInvertedPolarity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSpecialDataBits, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfSpecialDataBitsLeading, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfMultiTurnPositionBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSingleTurnPositionBits, unsigned short* pNbOfSpecialDataBitsTrailing, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, int* pCheckFrame, int* pReferenceReset, unsigned int* pErrorCode); - - //Safety - Configuration_DllExport int VCS_SetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int MaxFollowingError, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxFollowingError, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int MaxProfileVelocity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxProfileVelocity, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int MaxAcceleration, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxAcceleration, unsigned int* pErrorCode); - - //Controller Gains - Configuration_DllExport int VCS_SetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long Value, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long* pValue, unsigned int* pErrorCode); - - //Inputs/Outputs - 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); - 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); - Configuration_DllExport int VCS_AnalogInputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNb, unsigned short Configuration, int ExecutionMask, unsigned int* pErrorCode); - Configuration_DllExport int VCS_AnalogOutputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogOutputNb, unsigned short Configuration, unsigned int* pErrorCode); - - //Units - Configuration_DllExport int VCS_SetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char VelDimension, signed char VelNotation, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char* pVelDimension, char* pVelNotation, unsigned int* pErrorCode); - - //Compatibility Functions (do not use) - Configuration_DllExport int VCS_SetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned short D, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned short* pD, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); - - Configuration_DllExport int VCS_SetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); - Configuration_DllExport int VCS_SetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); - - Configuration_DllExport int VCS_SetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); - Configuration_DllExport int VCS_GetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); +//Motor +Configuration_DllExport int VCS_SetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short MotorType, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short NominalCurrent, unsigned short MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned int* pErrorCode); +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); +Configuration_DllExport int VCS_SetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int NominalCurrent, unsigned int MaxOutputCurrent, unsigned short ThermalTimeConstant, unsigned char NbOfPolePairs, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetMotorType(void* KeyHandle, unsigned short NodeId, unsigned short* pMotorType, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetDcMotorParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pNominalCurrent, unsigned short* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetDcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned int* pErrorCode); +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); +Configuration_DllExport int VCS_GetEcMotorParameterEx(void* KeyHandle, unsigned short NodeId, unsigned int* pNominalCurrent, unsigned int* pMaxOutputCurrent, unsigned short* pThermalTimeConstant, unsigned char* pNbOfPolePairs, unsigned int* pErrorCode); + +//Sensor +Configuration_DllExport int VCS_SetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short SensorType, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int EncoderResolution, int InvertedPolarity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int InvertedPolarity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, int InvertedPolarity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSpecialDataBits, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short DataRate, unsigned short NbOfSpecialDataBitsLeading, unsigned short NbOfMultiTurnDataBits, unsigned short NbOfMultiTurnPositionBits, unsigned short NbOfSingleTurnDataBits, unsigned short NbOfSingleTurnPositionBits, unsigned short NbOfSpecialDataBitsTrailing, int InvertedPolarity, unsigned short Timeout, unsigned short PowerupTime, int CheckFrame, int ReferenceReset, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetSensorType(void* KeyHandle, unsigned short NodeId, unsigned short* pSensorType, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetIncEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pEncoderResolution, int* pInvertedPolarity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetHallSensorParameter(void* KeyHandle, unsigned short NodeId, int* pInvertedPolarity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetSsiAbsEncoderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, int* pInvertedPolarity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetSsiAbsEncoderParameterEx(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSpecialDataBits, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetSsiAbsEncoderParameterEx2(void* KeyHandle, unsigned short NodeId, unsigned short* pDataRate, unsigned short* pNbOfSpecialDataBitsLeading, unsigned short* pNbOfMultiTurnDataBits, unsigned short* pNbOfMultiTurnPositionBits, unsigned short* pNbOfSingleTurnDataBits, unsigned short* pNbOfSingleTurnPositionBits, unsigned short* pNbOfSpecialDataBitsTrailing, int* pInvertedPolarity, unsigned short* pTimeout, unsigned short* pPowerupTime, int* pCheckFrame, int* pReferenceReset, unsigned int* pErrorCode); + +//Safety +Configuration_DllExport int VCS_SetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int MaxFollowingError, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetMaxFollowingError(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxFollowingError, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int MaxProfileVelocity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetMaxProfileVelocity(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxProfileVelocity, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int MaxAcceleration, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetMaxAcceleration(void* KeyHandle, unsigned short NodeId, unsigned int* pMaxAcceleration, unsigned int* pErrorCode); + +//Controller Gains +Configuration_DllExport int VCS_SetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long Value, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetControllerGain(void* KeyHandle, unsigned short NodeId, unsigned short EController, unsigned short EGain, unsigned long long* pValue, unsigned int* pErrorCode); + +//Inputs/Outputs +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); +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); +Configuration_DllExport int VCS_AnalogInputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNb, unsigned short Configuration, int ExecutionMask, unsigned int* pErrorCode); +Configuration_DllExport int VCS_AnalogOutputConfiguration(void* KeyHandle, unsigned short NodeId, unsigned short AnalogOutputNb, unsigned short Configuration, unsigned int* pErrorCode); + +//Units +Configuration_DllExport int VCS_SetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char VelDimension, signed char VelNotation, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetVelocityUnits(void* KeyHandle, unsigned short NodeId, unsigned char* pVelDimension, char* pVelNotation, unsigned int* pErrorCode); + +//Compatibility Functions (do not use) +Configuration_DllExport int VCS_SetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned short D, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetPositionRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned short* pD, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetPositionRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); + +Configuration_DllExport int VCS_SetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); +Configuration_DllExport int VCS_SetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short VelocityFeedForward, unsigned short AccelerationFeedForward, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetVelocityRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetVelocityRegulatorFeedForward(void* KeyHandle, unsigned short NodeId, unsigned short* pVelocityFeedForward, unsigned short* pAccelerationFeedForward, unsigned int* pErrorCode); + +Configuration_DllExport int VCS_SetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short P, unsigned short I, unsigned int* pErrorCode); +Configuration_DllExport int VCS_GetCurrentRegulatorGain(void* KeyHandle, unsigned short NodeId, unsigned short* pP, unsigned short* pI, unsigned int* pErrorCode); /************************************************************************************************************************************* * OPERATION FUNCTIONS *************************************************************************************************************************************/ //OperationMode - Status_DllExport int VCS_SetOperationMode(void* KeyHandle, unsigned short NodeId, char OperationMode, unsigned int* pErrorCode); - Status_DllExport int VCS_GetOperationMode(void* KeyHandle, unsigned short NodeId, char* pOperationMode, unsigned int* pErrorCode); +Status_DllExport int VCS_SetOperationMode(void* KeyHandle, unsigned short NodeId, char OperationMode, unsigned int* pErrorCode); +Status_DllExport int VCS_GetOperationMode(void* KeyHandle, unsigned short NodeId, char* pOperationMode, unsigned int* pErrorCode); //StateMachine - StateMachine_DllExport int VCS_ResetDevice(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_SetState(void* KeyHandle, unsigned short NodeId, unsigned short State, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_SetEnableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_SetDisableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_SetQuickStopState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_ClearFault(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_GetState(void* KeyHandle, unsigned short NodeId, unsigned short* pState, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_GetEnableState(void* KeyHandle, unsigned short NodeId, int* pIsEnabled, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_GetDisableState(void* KeyHandle, unsigned short NodeId, int* pIsDisabled, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_GetQuickStopState(void* KeyHandle, unsigned short NodeId, int* pIsQuickStopped, unsigned int* pErrorCode); - StateMachine_DllExport int VCS_GetFaultState(void* KeyHandle, unsigned short NodeId, int* pIsInFault, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_ResetDevice(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_SetState(void* KeyHandle, unsigned short NodeId, unsigned short State, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_SetEnableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_SetDisableState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_SetQuickStopState(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_ClearFault(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_GetState(void* KeyHandle, unsigned short NodeId, unsigned short* pState, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_GetEnableState(void* KeyHandle, unsigned short NodeId, int* pIsEnabled, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_GetDisableState(void* KeyHandle, unsigned short NodeId, int* pIsDisabled, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_GetQuickStopState(void* KeyHandle, unsigned short NodeId, int* pIsQuickStopped, unsigned int* pErrorCode); +StateMachine_DllExport int VCS_GetFaultState(void* KeyHandle, unsigned short NodeId, int* pIsInFault, unsigned int* pErrorCode); //ErrorHandling - ErrorHandling_DllExport int VCS_GetNbOfDeviceError(void* KeyHandle, unsigned short NodeId, unsigned char *pNbDeviceError, unsigned int *pErrorCode); - ErrorHandling_DllExport int VCS_GetDeviceErrorCode(void* KeyHandle, unsigned short NodeId, unsigned char DeviceErrorNumber, unsigned int *pDeviceErrorCode, unsigned int *pErrorCode); +ErrorHandling_DllExport int VCS_GetNbOfDeviceError(void* KeyHandle, unsigned short NodeId, unsigned char *pNbDeviceError, unsigned int *pErrorCode); +ErrorHandling_DllExport int VCS_GetDeviceErrorCode(void* KeyHandle, unsigned short NodeId, unsigned char DeviceErrorNumber, unsigned int *pDeviceErrorCode, unsigned int *pErrorCode); //Motion Info - MotionInfo_DllExport int VCS_GetMovementState(void* KeyHandle, unsigned short NodeId, int* pTargetReached, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_GetPositionIs(void* KeyHandle, unsigned short NodeId, int* pPositionIs, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_GetVelocityIs(void* KeyHandle, unsigned short NodeId, int* pVelocityIs, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_GetVelocityIsAveraged(void* KeyHandle, unsigned short NodeId, int* pVelocityIsAveraged, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_GetCurrentIs(void* KeyHandle, unsigned short NodeId, short* pCurrentIs, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_GetCurrentIsEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIs, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_GetCurrentIsAveraged(void* KeyHandle, unsigned short NodeId, short* pCurrentIsAveraged, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_GetCurrentIsAveragedEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIsAveraged, unsigned int* pErrorCode); - MotionInfo_DllExport int VCS_WaitForTargetReached(void* KeyHandle, unsigned short NodeId, unsigned int Timeout, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetMovementState(void* KeyHandle, unsigned short NodeId, int* pTargetReached, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetPositionIs(void* KeyHandle, unsigned short NodeId, int* pPositionIs, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetVelocityIs(void* KeyHandle, unsigned short NodeId, int* pVelocityIs, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetVelocityIsAveraged(void* KeyHandle, unsigned short NodeId, int* pVelocityIsAveraged, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetCurrentIs(void* KeyHandle, unsigned short NodeId, short* pCurrentIs, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetCurrentIsEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIs, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetCurrentIsAveraged(void* KeyHandle, unsigned short NodeId, short* pCurrentIsAveraged, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_GetCurrentIsAveragedEx(void* KeyHandle, unsigned short NodeId, int* pCurrentIsAveraged, unsigned int* pErrorCode); +MotionInfo_DllExport int VCS_WaitForTargetReached(void* KeyHandle, unsigned short NodeId, unsigned int Timeout, unsigned int* pErrorCode); //Profile Position Mode - ProfilePositionMode_DllExport int VCS_ActivateProfilePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - ProfilePositionMode_DllExport int VCS_SetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileVelocity, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); - ProfilePositionMode_DllExport int VCS_GetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileVelocity, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); - ProfilePositionMode_DllExport int VCS_MoveToPosition(void* KeyHandle, unsigned short NodeId, long TargetPosition, int Absolute, int Immediately, unsigned int* pErrorCode); - ProfilePositionMode_DllExport int VCS_GetTargetPosition(void* KeyHandle, unsigned short NodeId, long* pTargetPosition, unsigned int* pErrorCode); - ProfilePositionMode_DllExport int VCS_HaltPositionMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +ProfilePositionMode_DllExport int VCS_ActivateProfilePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +ProfilePositionMode_DllExport int VCS_SetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileVelocity, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); +ProfilePositionMode_DllExport int VCS_GetPositionProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileVelocity, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); +ProfilePositionMode_DllExport int VCS_MoveToPosition(void* KeyHandle, unsigned short NodeId, long TargetPosition, int Absolute, int Immediately, unsigned int* pErrorCode); +ProfilePositionMode_DllExport int VCS_GetTargetPosition(void* KeyHandle, unsigned short NodeId, long* pTargetPosition, unsigned int* pErrorCode); +ProfilePositionMode_DllExport int VCS_HaltPositionMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - //Advanced Functions - ProfilePositionMode_DllExport int VCS_EnablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int PositionWindow, unsigned short PositionWindowTime, unsigned int* pErrorCode); - ProfilePositionMode_DllExport int VCS_DisablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +//Advanced Functions +ProfilePositionMode_DllExport int VCS_EnablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int PositionWindow, unsigned short PositionWindowTime, unsigned int* pErrorCode); +ProfilePositionMode_DllExport int VCS_DisablePositionWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Profile Velocity Mode - ProfileVelocityMode_DllExport int VCS_ActivateProfileVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - ProfileVelocityMode_DllExport int VCS_SetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); - ProfileVelocityMode_DllExport int VCS_GetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); - ProfileVelocityMode_DllExport int VCS_MoveWithVelocity(void* KeyHandle, unsigned short NodeId, long TargetVelocity, unsigned int* pErrorCode); - ProfileVelocityMode_DllExport int VCS_GetTargetVelocity(void* KeyHandle, unsigned short NodeId, long* pTargetVelocity, unsigned int* pErrorCode); - ProfileVelocityMode_DllExport int VCS_HaltVelocityMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +ProfileVelocityMode_DllExport int VCS_ActivateProfileVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +ProfileVelocityMode_DllExport int VCS_SetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int ProfileAcceleration, unsigned int ProfileDeceleration, unsigned int* pErrorCode); +ProfileVelocityMode_DllExport int VCS_GetVelocityProfile(void* KeyHandle, unsigned short NodeId, unsigned int* pProfileAcceleration, unsigned int* pProfileDeceleration, unsigned int* pErrorCode); +ProfileVelocityMode_DllExport int VCS_MoveWithVelocity(void* KeyHandle, unsigned short NodeId, long TargetVelocity, unsigned int* pErrorCode); +ProfileVelocityMode_DllExport int VCS_GetTargetVelocity(void* KeyHandle, unsigned short NodeId, long* pTargetVelocity, unsigned int* pErrorCode); +ProfileVelocityMode_DllExport int VCS_HaltVelocityMovement(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - //Advanced Functions - ProfileVelocityMode_DllExport int VCS_EnableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int VelocityWindow, unsigned short VelocityWindowTime, unsigned int* pErrorCode); - ProfileVelocityMode_DllExport int VCS_DisableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +//Advanced Functions +ProfileVelocityMode_DllExport int VCS_EnableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int VelocityWindow, unsigned short VelocityWindowTime, unsigned int* pErrorCode); +ProfileVelocityMode_DllExport int VCS_DisableVelocityWindow(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Homing Mode - HomingMode_DllExport int VCS_ActivateHomingMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - HomingMode_DllExport int VCS_SetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int HomingAcceleration, unsigned int SpeedSwitch, unsigned int SpeedIndex, int HomeOffset, unsigned short CurrentThreshold, int HomePosition, unsigned int* pErrorCode); - HomingMode_DllExport int VCS_GetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pHomingAcceleration, unsigned int* pSpeedSwitch, unsigned int* pSpeedIndex, int* pHomeOffset, unsigned short* pCurrentThreshold, int* pHomePosition, unsigned int* pErrorCode); - HomingMode_DllExport int VCS_FindHome(void* KeyHandle, unsigned short NodeId, signed char HomingMethod, unsigned int* pErrorCode); - HomingMode_DllExport int VCS_StopHoming(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - HomingMode_DllExport int VCS_DefinePosition(void* KeyHandle, unsigned short NodeId, int HomePosition, unsigned int* pErrorCode); - HomingMode_DllExport int VCS_WaitForHomingAttained(void* KeyHandle, unsigned short NodeId, int Timeout, unsigned int* pErrorCode); - HomingMode_DllExport int VCS_GetHomingState(void* KeyHandle, unsigned short NodeId, int* pHomingAttained, int* pHomingError, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_ActivateHomingMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_SetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int HomingAcceleration, unsigned int SpeedSwitch, unsigned int SpeedIndex, int HomeOffset, unsigned short CurrentThreshold, int HomePosition, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_GetHomingParameter(void* KeyHandle, unsigned short NodeId, unsigned int* pHomingAcceleration, unsigned int* pSpeedSwitch, unsigned int* pSpeedIndex, int* pHomeOffset, unsigned short* pCurrentThreshold, int* pHomePosition, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_FindHome(void* KeyHandle, unsigned short NodeId, signed char HomingMethod, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_StopHoming(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_DefinePosition(void* KeyHandle, unsigned short NodeId, int HomePosition, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_WaitForHomingAttained(void* KeyHandle, unsigned short NodeId, int Timeout, unsigned int* pErrorCode); +HomingMode_DllExport int VCS_GetHomingState(void* KeyHandle, unsigned short NodeId, int* pHomingAttained, int* pHomingError, unsigned int* pErrorCode); //Interpolated Position Mode - InterpolatedPositionMode_DllExport int VCS_ActivateInterpolatedPositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - InterpolatedPositionMode_DllExport int VCS_SetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short UnderflowWarningLimit, unsigned short OverflowWarningLimit, unsigned int* pErrorCode); - InterpolatedPositionMode_DllExport int VCS_GetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pUnderflowWarningLimit, unsigned short* pOverflowWarningLimit, unsigned int* pMaxBufferSize, unsigned int* pErrorCode); - InterpolatedPositionMode_DllExport int VCS_ClearIpmBuffer(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - InterpolatedPositionMode_DllExport int VCS_GetFreeIpmBufferSize(void* KeyHandle, unsigned short NodeId, unsigned int* pBufferSize, unsigned int* pErrorCode); - InterpolatedPositionMode_DllExport int VCS_AddPvtValueToIpmBuffer(void* KeyHandle, unsigned short NodeId, long Position, long Velocity, unsigned char Time, unsigned int* pErrorCode); - InterpolatedPositionMode_DllExport int VCS_StartIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - InterpolatedPositionMode_DllExport int VCS_StopIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - 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); +InterpolatedPositionMode_DllExport int VCS_ActivateInterpolatedPositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +InterpolatedPositionMode_DllExport int VCS_SetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short UnderflowWarningLimit, unsigned short OverflowWarningLimit, unsigned int* pErrorCode); +InterpolatedPositionMode_DllExport int VCS_GetIpmBufferParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pUnderflowWarningLimit, unsigned short* pOverflowWarningLimit, unsigned int* pMaxBufferSize, unsigned int* pErrorCode); +InterpolatedPositionMode_DllExport int VCS_ClearIpmBuffer(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +InterpolatedPositionMode_DllExport int VCS_GetFreeIpmBufferSize(void* KeyHandle, unsigned short NodeId, unsigned int* pBufferSize, unsigned int* pErrorCode); +InterpolatedPositionMode_DllExport int VCS_AddPvtValueToIpmBuffer(void* KeyHandle, unsigned short NodeId, long Position, long Velocity, unsigned char Time, unsigned int* pErrorCode); +InterpolatedPositionMode_DllExport int VCS_StartIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +InterpolatedPositionMode_DllExport int VCS_StopIpmTrajectory(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +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); //Position Mode - PositionMode_DllExport int VCS_ActivatePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - PositionMode_DllExport int VCS_SetPositionMust(void* KeyHandle, unsigned short NodeId, long PositionMust, unsigned int* pErrorCode); - PositionMode_DllExport int VCS_GetPositionMust(void* KeyHandle, unsigned short NodeId, long* pPositionMust, unsigned int* pErrorCode); +PositionMode_DllExport int VCS_ActivatePositionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +PositionMode_DllExport int VCS_SetPositionMust(void* KeyHandle, unsigned short NodeId, long PositionMust, unsigned int* pErrorCode); +PositionMode_DllExport int VCS_GetPositionMust(void* KeyHandle, unsigned short NodeId, long* pPositionMust, unsigned int* pErrorCode); - //Advanced Functions - PositionMode_DllExport int VCS_ActivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); - PositionMode_DllExport int VCS_DeactivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); - PositionMode_DllExport int VCS_EnableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - PositionMode_DllExport int VCS_DisableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +//Advanced Functions +PositionMode_DllExport int VCS_ActivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); +PositionMode_DllExport int VCS_DeactivateAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); +PositionMode_DllExport int VCS_EnableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +PositionMode_DllExport int VCS_DisableAnalogPositionSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Velocity Mode - VelocityMode_DllExport int VCS_ActivateVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - VelocityMode_DllExport int VCS_SetVelocityMust(void* KeyHandle, unsigned short NodeId, long VelocityMust, unsigned int* pErrorCode); - VelocityMode_DllExport int VCS_GetVelocityMust(void* KeyHandle, unsigned short NodeId, long* pVelocityMust, unsigned int* pErrorCode); +VelocityMode_DllExport int VCS_ActivateVelocityMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +VelocityMode_DllExport int VCS_SetVelocityMust(void* KeyHandle, unsigned short NodeId, long VelocityMust, unsigned int* pErrorCode); +VelocityMode_DllExport int VCS_GetVelocityMust(void* KeyHandle, unsigned short NodeId, long* pVelocityMust, unsigned int* pErrorCode); - //Advanced Functions - VelocityMode_DllExport int VCS_ActivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); - VelocityMode_DllExport int VCS_DeactivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); - VelocityMode_DllExport int VCS_EnableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - VelocityMode_DllExport int VCS_DisableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +//Advanced Functions +VelocityMode_DllExport int VCS_ActivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, long Offset, unsigned int* pErrorCode); +VelocityMode_DllExport int VCS_DeactivateAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); +VelocityMode_DllExport int VCS_EnableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +VelocityMode_DllExport int VCS_DisableAnalogVelocitySetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //Current Mode - CurrentMode_DllExport int VCS_ActivateCurrentMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - CurrentMode_DllExport int VCS_SetCurrentMust(void* KeyHandle, unsigned short NodeId, short CurrentMust, unsigned int* pErrorCode); - CurrentMode_DllExport int VCS_SetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int CurrentMust, unsigned int* pErrorCode); - CurrentMode_DllExport int VCS_GetCurrentMust(void* KeyHandle, unsigned short NodeId, short* pCurrentMust, unsigned int* pErrorCode); - CurrentMode_DllExport int VCS_GetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int* pCurrentMust, unsigned int* pErrorCode); - - //Advanced Functions - CurrentMode_DllExport int VCS_ActivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, short Offset, unsigned int* pErrorCode); - CurrentMode_DllExport int VCS_DeactivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); - CurrentMode_DllExport int VCS_EnableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - CurrentMode_DllExport int VCS_DisableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_ActivateCurrentMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_SetCurrentMust(void* KeyHandle, unsigned short NodeId, short CurrentMust, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_SetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int CurrentMust, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_GetCurrentMust(void* KeyHandle, unsigned short NodeId, short* pCurrentMust, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_GetCurrentMustEx(void* KeyHandle, unsigned short NodeId, int* pCurrentMust, unsigned int* pErrorCode); + +//Advanced Functions +CurrentMode_DllExport int VCS_ActivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, float Scaling, short Offset, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_DeactivateAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned short AnalogInputNumber, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_EnableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +CurrentMode_DllExport int VCS_DisableAnalogCurrentSetpoint(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //MasterEncoder Mode - MasterEncoderMode_DllExport int VCS_ActivateMasterEncoderMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - 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); - 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); +MasterEncoderMode_DllExport int VCS_ActivateMasterEncoderMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +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); +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); //StepDirection Mode - StepDirectionMode_DllExport int VCS_ActivateStepDirectionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - 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); - 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); +StepDirectionMode_DllExport int VCS_ActivateStepDirectionMode(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +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); +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); //Inputs Outputs - //General - InputsOutputs_DllExport int VCS_GetAllDigitalInputs(void* KeyHandle, unsigned short NodeId, unsigned short* pInputs, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_GetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short* pOutputs, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_SetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short Outputs, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_GetAnalogInput(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, unsigned short* pAnalogValue, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_GetAnalogInputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, long* pVoltageValue, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_GetAnalogInputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long* pStateValue, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_SetAnalogOutput(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, unsigned short AnalogValue, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_SetAnalogOutputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, long VoltageValue, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_SetAnalogOutputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long StateValue, unsigned int* pErrorCode); - - //Position Compare - 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); - 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); - InputsOutputs_DllExport int VCS_ActivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, int Polarity, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_DeactivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_EnablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_DisablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_SetPositionCompareReferencePosition(void* KeyHandle, unsigned short NodeId, long ReferencePosition, unsigned int* pErrorCode); - - //Position Marker - InputsOutputs_DllExport int VCS_SetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char PositionMarkerEdgeType, unsigned char PositionMarkerMode, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_GetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char* pPositionMarkerEdgeType, unsigned char* pPositionMarkerMode, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_ActivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, int Polarity, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_DeactivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_ReadPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned short* pCount, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_ReadPositionMarkerCapturedPosition(void* KeyHandle, unsigned short NodeId, unsigned short CounterIndex, long* pCapturedPosition, unsigned int* pErrorCode); - InputsOutputs_DllExport int VCS_ResetPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +//General +InputsOutputs_DllExport int VCS_GetAllDigitalInputs(void* KeyHandle, unsigned short NodeId, unsigned short* pInputs, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_GetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short* pOutputs, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_SetAllDigitalOutputs(void* KeyHandle, unsigned short NodeId, unsigned short Outputs, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_GetAnalogInput(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, unsigned short* pAnalogValue, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_GetAnalogInputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short InputNumber, long* pVoltageValue, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_GetAnalogInputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long* pStateValue, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_SetAnalogOutput(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, unsigned short AnalogValue, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_SetAnalogOutputVoltage(void* KeyHandle, unsigned short NodeId, unsigned short OutputNumber, long VoltageValue, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_SetAnalogOutputState(void* KeyHandle, unsigned short NodeId, unsigned short Configuration, long StateValue, unsigned int* pErrorCode); + +//Position Compare +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); +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); +InputsOutputs_DllExport int VCS_ActivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, int Polarity, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_DeactivatePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned short DigitalOutputNumber, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_EnablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_DisablePositionCompare(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_SetPositionCompareReferencePosition(void* KeyHandle, unsigned short NodeId, long ReferencePosition, unsigned int* pErrorCode); + +//Position Marker +InputsOutputs_DllExport int VCS_SetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char PositionMarkerEdgeType, unsigned char PositionMarkerMode, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_GetPositionMarkerParameter(void* KeyHandle, unsigned short NodeId, unsigned char* pPositionMarkerEdgeType, unsigned char* pPositionMarkerMode, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_ActivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, int Polarity, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_DeactivatePositionMarker(void* KeyHandle, unsigned short NodeId, unsigned short DigitalInputNumber, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_ReadPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned short* pCount, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_ReadPositionMarkerCapturedPosition(void* KeyHandle, unsigned short NodeId, unsigned short CounterIndex, long* pCapturedPosition, unsigned int* pErrorCode); +InputsOutputs_DllExport int VCS_ResetPositionMarkerCounter(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); //******************************************************************************************************************* // DATA RECORDING FUNCTIONS //******************************************************************************************************************* - //DataRecorder Setup - DataRecording_DllExport int VCS_SetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short SamplingPeriod, unsigned short NbOfPrecedingSamples, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_GetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pSamplingPeriod, unsigned short* pNbOfPrecedingSamples, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_EnableTrigger(void* KeyHandle, unsigned short NodeId, unsigned char TriggerType, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_DisableAllTriggers(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_ActivateChannel(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned short ObjectIndex, unsigned char ObjectSubIndex, unsigned char ObjectSize, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_DeactivateAllChannels(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - - //DataRecorder Status - DataRecording_DllExport int VCS_StartRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_StopRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_ForceTrigger(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_IsRecorderRunning(void* KeyHandle, unsigned short NodeId, int* pRunning, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_IsRecorderTriggered(void* KeyHandle, unsigned short NodeId, int* pTriggered, unsigned int* pErrorCode); - - //DataRecorder Data - DataRecording_DllExport int VCS_ReadChannelVectorSize(void* KeyHandle, unsigned short NodeId, unsigned int* pVectorSize, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_ReadChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataVectorBuffer, unsigned int VectorBufferSize, unsigned int* pErrorCode); - - //Advanced Functions - DataRecording_DllExport int VCS_ReadDataBuffer(void* KeyHandle, unsigned short NodeId, unsigned char* pDataBuffer, unsigned int BufferSizeToRead, unsigned int* pBufferSizeRead, unsigned short* pVectorStartOffset, unsigned short* pMaxNbOfSamples, unsigned short* pNbOfRecordedSamples, unsigned int* pErrorCode); - DataRecording_DllExport int VCS_ExtractChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataBuffer, unsigned int BufferSize, unsigned char* pDataVector, unsigned int VectorSize, unsigned short VectorStartOffset, unsigned short MaxNbOfSamples, unsigned short NbOfRecordedSamples, unsigned int* pErrorCode); +//DataRecorder Setup +DataRecording_DllExport int VCS_SetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short SamplingPeriod, unsigned short NbOfPrecedingSamples, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_GetRecorderParameter(void* KeyHandle, unsigned short NodeId, unsigned short* pSamplingPeriod, unsigned short* pNbOfPrecedingSamples, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_EnableTrigger(void* KeyHandle, unsigned short NodeId, unsigned char TriggerType, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_DisableAllTriggers(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_ActivateChannel(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned short ObjectIndex, unsigned char ObjectSubIndex, unsigned char ObjectSize, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_DeactivateAllChannels(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); + +//DataRecorder Status +DataRecording_DllExport int VCS_StartRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_StopRecorder(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_ForceTrigger(void* KeyHandle, unsigned short NodeId, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_IsRecorderRunning(void* KeyHandle, unsigned short NodeId, int* pRunning, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_IsRecorderTriggered(void* KeyHandle, unsigned short NodeId, int* pTriggered, unsigned int* pErrorCode); + +//DataRecorder Data +DataRecording_DllExport int VCS_ReadChannelVectorSize(void* KeyHandle, unsigned short NodeId, unsigned int* pVectorSize, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_ReadChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataVectorBuffer, unsigned int VectorBufferSize, unsigned int* pErrorCode); + +//Advanced Functions +DataRecording_DllExport int VCS_ReadDataBuffer(void* KeyHandle, unsigned short NodeId, unsigned char* pDataBuffer, unsigned int BufferSizeToRead, unsigned int* pBufferSizeRead, unsigned short* pVectorStartOffset, unsigned short* pMaxNbOfSamples, unsigned short* pNbOfRecordedSamples, unsigned int* pErrorCode); +DataRecording_DllExport int VCS_ExtractChannelDataVector(void* KeyHandle, unsigned short NodeId, unsigned char ChannelNumber, unsigned char* pDataBuffer, unsigned int BufferSize, unsigned char* pDataVector, unsigned int VectorSize, unsigned short VectorStartOffset, unsigned short MaxNbOfSamples, unsigned short NbOfRecordedSamples, unsigned int* pErrorCode); /************************************************************************************************************************************* * LOW LAYER FUNCTIONS *************************************************************************************************************************************/ //CanLayer Functions - CanLayer_DllExport int VCS_SendCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); - CanLayer_DllExport int VCS_ReadCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int Timeout, unsigned int* pErrorCode); - CanLayer_DllExport int VCS_RequestCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); - CanLayer_DllExport int VCS_SendNMTService(void* KeyHandle, unsigned short NodeId, unsigned short CommandSpecifier, unsigned int* pErrorCode); +CanLayer_DllExport int VCS_SendCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); +CanLayer_DllExport int VCS_ReadCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int Timeout, unsigned int* pErrorCode); +CanLayer_DllExport int VCS_RequestCANFrame(void* KeyHandle, unsigned short CobID, unsigned short Length, void* pData, unsigned int* pErrorCode); +CanLayer_DllExport int VCS_SendNMTService(void* KeyHandle, unsigned short NodeId, unsigned short CommandSpecifier, unsigned int* pErrorCode); /************************************************************************************************************************************* * TYPE DEFINITIONS *************************************************************************************************************************************/ //Communication - //Dialog Mode - const int DM_PROGRESS_DLG = 0; - const int DM_PROGRESS_AND_CONFIRM_DLG = 1; - const int DM_CONFIRM_DLG = 2; - const int DM_NO_DLG = 3; +//Dialog Mode +extern const int DM_PROGRESS_DLG; //= 0; +extern const int DM_PROGRESS_AND_CONFIRM_DLG; //= 1; +extern const int DM_CONFIRM_DLG; //= 2; +extern const int DM_NO_DLG; //= 3; //Configuration - //MotorType - const unsigned short MT_DC_MOTOR = 1; - const unsigned short MT_EC_SINUS_COMMUTATED_MOTOR = 10; - const unsigned short MT_EC_BLOCK_COMMUTATED_MOTOR = 11; - - //SensorType - const unsigned short ST_UNKNOWN = 0; - const unsigned short ST_INC_ENCODER_3CHANNEL = 1; - const unsigned short ST_INC_ENCODER_2CHANNEL = 2; - const unsigned short ST_HALL_SENSORS = 3; - const unsigned short ST_SSI_ABS_ENCODER_BINARY = 4; - const unsigned short ST_SSI_ABS_ENCODER_GREY = 5; - const unsigned short ST_INC_ENCODER2_3CHANNEL = 6; - const unsigned short ST_INC_ENCODER2_2CHANNEL = 7; - const unsigned short ST_ANALOG_INC_ENCODER_3CHANNEL = 8; - const unsigned short ST_ANALOG_INC_ENCODER_2CHANNEL = 9; +//MotorType +extern const unsigned short MT_DC_MOTOR; //= 1; +extern const unsigned short MT_EC_SINUS_COMMUTATED_MOTOR; //= 10; +extern const unsigned short MT_EC_BLOCK_COMMUTATED_MOTOR; //= 11; + +//SensorType +extern const unsigned short ST_UNKNOWN; //= 0; +extern const unsigned short ST_INC_ENCODER_3CHANNEL; //= 1; +extern const unsigned short ST_INC_ENCODER_2CHANNEL; //= 2; +extern const unsigned short ST_HALL_SENSORS; //= 3; +extern const unsigned short ST_SSI_ABS_ENCODER_BINARY; //= 4; +extern const unsigned short ST_SSI_ABS_ENCODER_GREY; //= 5; +extern const unsigned short ST_INC_ENCODER2_3CHANNEL; //= 6; +extern const unsigned short ST_INC_ENCODER2_2CHANNEL; //= 7; +extern const unsigned short ST_ANALOG_INC_ENCODER_3CHANNEL; //= 8; +extern const unsigned short ST_ANALOG_INC_ENCODER_2CHANNEL; //= 9; //In- and outputs - //Digital input configuration - const unsigned short DIC_NEGATIVE_LIMIT_SWITCH = 0; - const unsigned short DIC_POSITIVE_LIMIT_SWITCH = 1; - const unsigned short DIC_HOME_SWITCH = 2; - const unsigned short DIC_POSITION_MARKER = 3; - const unsigned short DIC_DRIVE_ENABLE = 4; - const unsigned short DIC_QUICK_STOP = 5; - const unsigned short DIC_GENERAL_PURPOSE_J = 6; - const unsigned short DIC_GENERAL_PURPOSE_I = 7; - const unsigned short DIC_GENERAL_PURPOSE_H = 8; - const unsigned short DIC_GENERAL_PURPOSE_G = 9; - const unsigned short DIC_GENERAL_PURPOSE_F = 10; - const unsigned short DIC_GENERAL_PURPOSE_E = 11; - const unsigned short DIC_GENERAL_PURPOSE_D = 12; - const unsigned short DIC_GENERAL_PURPOSE_C = 13; - const unsigned short DIC_GENERAL_PURPOSE_B = 14; - const unsigned short DIC_GENERAL_PURPOSE_A = 15; - - //Digital output configuration - const unsigned short DOC_READY_FAULT = 0; - const unsigned short DOC_POSITION_COMPARE = 1; - const unsigned short DOC_GENERAL_PURPOSE_H = 8; - const unsigned short DOC_GENERAL_PURPOSE_G = 9; - const unsigned short DOC_GENERAL_PURPOSE_F = 10; - const unsigned short DOC_GENERAL_PURPOSE_E = 11; - const unsigned short DOC_GENERAL_PURPOSE_D = 12; - const unsigned short DOC_GENERAL_PURPOSE_C = 13; - const unsigned short DOC_GENERAL_PURPOSE_B = 14; - const unsigned short DOC_GENERAL_PURPOSE_A = 15; - - //Analog input configuration - const unsigned short AIC_ANALOG_CURRENT_SETPOINT = 0; - const unsigned short AIC_ANALOG_VELOCITY_SETPOINT = 1; - const unsigned short AIC_ANALOG_POSITION_SETPOINT = 2; - const unsigned short AIC_GENERAL_PURPOSE_H = 8; - const unsigned short AIC_GENERAL_PURPOSE_G = 9; - const unsigned short AIC_GENERAL_PURPOSE_F = 10; - const unsigned short AIC_GENERAL_PURPOSE_E = 11; - const unsigned short AIC_GENERAL_PURPOSE_D = 12; - const unsigned short AIC_GENERAL_PURPOSE_C = 13; - const unsigned short AIC_GENERAL_PURPOSE_B = 14; - const unsigned short AIC_GENERAL_PURPOSE_A = 15; - - //Analog output configuration - const unsigned short AOC_GENERAL_PURPOSE_A = 0; - const unsigned short AOC_GENERAL_PURPOSE_B = 1; +//Digital input configuration +extern const unsigned short DIC_NEGATIVE_LIMIT_SWITCH; //= 0; +extern const unsigned short DIC_POSITIVE_LIMIT_SWITCH; //= 1; +extern const unsigned short DIC_HOME_SWITCH; //= 2; +extern const unsigned short DIC_POSITION_MARKER; //= 3; +extern const unsigned short DIC_DRIVE_ENABLE; //= 4; +extern const unsigned short DIC_QUICK_STOP; //= 5; +extern const unsigned short DIC_GENERAL_PURPOSE_J; //= 6; +extern const unsigned short DIC_GENERAL_PURPOSE_I; //= 7; +extern const unsigned short DIC_GENERAL_PURPOSE_H; //= 8; +extern const unsigned short DIC_GENERAL_PURPOSE_G; //= 9; +extern const unsigned short DIC_GENERAL_PURPOSE_F; //= 10; +extern const unsigned short DIC_GENERAL_PURPOSE_E; //= 11; +extern const unsigned short DIC_GENERAL_PURPOSE_D; //= 12; +extern const unsigned short DIC_GENERAL_PURPOSE_C; //= 13; +extern const unsigned short DIC_GENERAL_PURPOSE_B; //= 14; +extern const unsigned short DIC_GENERAL_PURPOSE_A; //= 15; + +//Digital output configuration +extern const unsigned short DOC_READY_FAULT; //= 0; +extern const unsigned short DOC_POSITION_COMPARE; //= 1; +extern const unsigned short DOC_GENERAL_PURPOSE_H; //= 8; +extern const unsigned short DOC_GENERAL_PURPOSE_G; //= 9; +extern const unsigned short DOC_GENERAL_PURPOSE_F; //= 10; +extern const unsigned short DOC_GENERAL_PURPOSE_E; //= 11; +extern const unsigned short DOC_GENERAL_PURPOSE_D; //= 12; +extern const unsigned short DOC_GENERAL_PURPOSE_C; //= 13; +extern const unsigned short DOC_GENERAL_PURPOSE_B; //= 14; +extern const unsigned short DOC_GENERAL_PURPOSE_A; //= 15; + +//Analog input configuration +extern const unsigned short AIC_ANALOG_CURRENT_SETPOINT; //= 0; +extern const unsigned short AIC_ANALOG_VELOCITY_SETPOINT; //= 1; +extern const unsigned short AIC_ANALOG_POSITION_SETPOINT; //= 2; +extern const unsigned short AIC_GENERAL_PURPOSE_H; //= 8; +extern const unsigned short AIC_GENERAL_PURPOSE_G; //= 9; +extern const unsigned short AIC_GENERAL_PURPOSE_F; //= 10; +extern const unsigned short AIC_GENERAL_PURPOSE_E; //= 11; +extern const unsigned short AIC_GENERAL_PURPOSE_D; //= 12; +extern const unsigned short AIC_GENERAL_PURPOSE_C; //= 13; +extern const unsigned short AIC_GENERAL_PURPOSE_B; //= 14; +extern const unsigned short AIC_GENERAL_PURPOSE_A; //= 15; + +//Analog output configuration +extern const unsigned short AOC_GENERAL_PURPOSE_A; //= 0; +extern const unsigned short AOC_GENERAL_PURPOSE_B; //= 1; //Units - //VelocityDimension - const unsigned char VD_RPM = 0xA4; +//VelocityDimension +extern const unsigned char VD_RPM; //= 0xA4; - //VelocityNotation - const signed char VN_STANDARD = 0; - const signed char VN_DECI = -1; - const signed char VN_CENTI = -2; - const signed char VN_MILLI = -3; +//VelocityNotation +extern const signed char VN_STANDARD; //= 0; +extern const signed char VN_DECI; //= -1; +extern const signed char VN_CENTI; //= -2; +extern const signed char VN_MILLI; //= -3; //Operational mode - const signed char OMD_PROFILE_POSITION_MODE = 1; - const signed char OMD_PROFILE_VELOCITY_MODE = 3; - const signed char OMD_HOMING_MODE = 6; - const signed char OMD_INTERPOLATED_POSITION_MODE = 7; - const signed char OMD_POSITION_MODE = -1; - const signed char OMD_VELOCITY_MODE = -2; - const signed char OMD_CURRENT_MODE = -3; - const signed char OMD_MASTER_ENCODER_MODE = -5; - const signed char OMD_STEP_DIRECTION_MODE = -6; +extern const signed char OMD_PROFILE_POSITION_MODE; //= 1; +extern const signed char OMD_PROFILE_VELOCITY_MODE; //= 3; +extern const signed char OMD_HOMING_MODE; //= 6; +extern const signed char OMD_INTERPOLATED_POSITION_MODE; //; //= 7; +extern const signed char OMD_POSITION_MODE; //= -1; +extern const signed char OMD_VELOCITY_MODE; //= -2; +extern const signed char OMD_CURRENT_MODE; //; //= -3; +extern const signed char OMD_MASTER_ENCODER_MODE; //= -5; +extern const signed char OMD_STEP_DIRECTION_MODE; //= -6; //States - const unsigned short ST_DISABLED = 0; - const unsigned short ST_ENABLED = 1; - const unsigned short ST_QUICKSTOP = 2; - const unsigned short ST_FAULT = 3; +extern const unsigned short ST_DISABLED; //= 0; +extern const unsigned short ST_ENABLED; //= 1; +extern const unsigned short ST_QUICKSTOP; //= 2; +extern const unsigned short ST_FAULT; //= 3; //Homing mode - //Homing method - const char HM_ACTUAL_POSITION = 35; - const char HM_NEGATIVE_LIMIT_SWITCH = 17; - const char HM_NEGATIVE_LIMIT_SWITCH_AND_INDEX = 1; - const char HM_POSITIVE_LIMIT_SWITCH = 18; - const char HM_POSITIVE_LIMIT_SWITCH_AND_INDEX = 2; - const char HM_HOME_SWITCH_POSITIVE_SPEED = 23; - const char HM_HOME_SWITCH_POSITIVE_SPEED_AND_INDEX = 7; - const char HM_HOME_SWITCH_NEGATIVE_SPEED = 27; - const char HM_HOME_SWITCH_NEGATIVE_SPEED_AND_INDEX = 11; - const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED = -3; - const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED_AND_INDEX = -1; - const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED = -4; - const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED_AND_INDEX = -2; - const char HM_INDEX_POSITIVE_SPEED = 34; - const char HM_INDEX_NEGATIVE_SPEED = 33; +//Homing method +extern const char HM_ACTUAL_POSITION; //= 35; +extern const char HM_NEGATIVE_LIMIT_SWITCH; //= 17; +extern const char HM_NEGATIVE_LIMIT_SWITCH_AND_INDEX; //= 1; +extern const char HM_POSITIVE_LIMIT_SWITCH; //= 18; +extern const char HM_POSITIVE_LIMIT_SWITCH_AND_INDEX; //= 2; +extern const char HM_HOME_SWITCH_POSITIVE_SPEED; //= 23; +extern const char HM_HOME_SWITCH_POSITIVE_SPEED_AND_INDEX; //= 7; +extern const char HM_HOME_SWITCH_NEGATIVE_SPEED; //= 27; +extern const char HM_HOME_SWITCH_NEGATIVE_SPEED_AND_INDEX; //= 11; +extern const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED; //= -3; +extern const char HM_CURRENT_THRESHOLD_POSITIVE_SPEED_AND_INDEX; //= -1; +extern const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED; //= -4; +extern const char HM_CURRENT_THRESHOLD_NEGATIVE_SPEED_AND_INDEX; //= -2; +extern const char HM_INDEX_POSITIVE_SPEED; //= 34; +extern const char HM_INDEX_NEGATIVE_SPEED; //= 33; //Input Output PositionMarker - //PositionMarkerEdgeType - const unsigned char PET_BOTH_EDGES = 0; - const unsigned char PET_RISING_EDGE = 1; - const unsigned char PET_FALLING_EDGE = 2; +//PositionMarkerEdgeType +extern const unsigned char PET_BOTH_EDGES; //= 0; +extern const unsigned char PET_RISING_EDGE; //= 1; +extern const unsigned char PET_FALLING_EDGE; //= 2; - //PositionMarkerMode - const unsigned char PM_CONTINUOUS = 0; - const unsigned char PM_SINGLE = 1; - const unsigned char PM_MULTIPLE = 2; +//PositionMarkerMode +extern const unsigned char PM_CONTINUOUS; //= 0; +extern const unsigned char PM_SINGLE; //= 1; +extern const unsigned char PM_MULTIPLE; //= 2; //Input Output PositionCompare - //PositionCompareOperationalMode - const unsigned char PCO_SINGLE_POSITION_MODE = 0; - const unsigned char PCO_POSITION_SEQUENCE_MODE = 1; +//PositionCompareOperationalMode +extern const unsigned char PCO_SINGLE_POSITION_MODE; //= 0; +extern const unsigned char PCO_POSITION_SEQUENCE_MODE; //= 1; - //PositionCompareIntervalMode - const unsigned char PCI_NEGATIVE_DIR_TO_REFPOS = 0; - const unsigned char PCI_POSITIVE_DIR_TO_REFPOS = 1; - const unsigned char PCI_BOTH_DIR_TO_REFPOS = 2; +//PositionCompareIntervalMode +extern const unsigned char PCI_NEGATIVE_DIR_TO_REFPOS; //= 0; +extern const unsigned char PCI_POSITIVE_DIR_TO_REFPOS; //; //= 1; +extern const unsigned char PCI_BOTH_DIR_TO_REFPOS; //; //= 2; - //PositionCompareDirectionDependency - const unsigned char PCD_MOTOR_DIRECTION_NEGATIVE = 0; - const unsigned char PCD_MOTOR_DIRECTION_POSITIVE = 1; - const unsigned char PCD_MOTOR_DIRECTION_BOTH = 2; +//PositionCompareDirectionDependency +extern const unsigned char PCD_MOTOR_DIRECTION_NEGATIVE; //= 0; +extern const unsigned char PCD_MOTOR_DIRECTION_POSITIVE; //= 1; +extern const unsigned char PCD_MOTOR_DIRECTION_BOTH; //= 2; //Data recorder - //Trigger type - const unsigned short DR_MOVEMENT_START_TRIGGER = 1; //bit 1 - const unsigned short DR_ERROR_TRIGGER = 2; //bit 2 - const unsigned short DR_DIGITAL_INPUT_TRIGGER = 4; //bit 3 - const unsigned short DR_MOVEMENT_END_TRIGGER = 8; //bit 4 +//Trigger type +extern const unsigned short DR_MOVEMENT_START_TRIGGER; //= 1;//bit 1 +extern const unsigned short DR_ERROR_TRIGGER; //= 2;//bit 2 +extern const unsigned short DR_DIGITAL_INPUT_TRIGGER; //= 4;//bit 3 +extern const unsigned short DR_MOVEMENT_END_TRIGGER; //= 8;//bit 4 //CanLayer Functions - const unsigned short NCS_START_REMOTE_NODE = 1; - const unsigned short NCS_STOP_REMOTE_NODE = 2; - const unsigned short NCS_ENTER_PRE_OPERATIONAL = 128; - const unsigned short NCS_RESET_NODE = 129; - const unsigned short NCS_RESET_COMMUNICATION = 130; +extern const unsigned short NCS_START_REMOTE_NODE; //= 1; +extern const unsigned short NCS_STOP_REMOTE_NODE; //= 2; +extern const unsigned short NCS_ENTER_PRE_OPERATIONAL; //= 128; +extern const unsigned short NCS_RESET_NODE; //= 129; +extern const unsigned short NCS_RESET_COMMUNICATION; //= 130; // Controller Gains - // EController - const unsigned short EC_PI_CURRENT_CONTROLLER = 1; - const unsigned short EC_PI_VELOCITY_CONTROLLER = 10; - const unsigned short EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER = 11; - const unsigned short EC_PID_POSITION_CONTROLLER = 20; - const unsigned short EC_DUAL_LOOP_POSITION_CONTROLLER = 21; - - // EGain (EC_PI_CURRENT_CONTROLLER) - const unsigned short EG_PICC_P_GAIN = 1; - const unsigned short EG_PICC_I_GAIN = 2; - - // EGain (EC_PI_VELOCITY_CONTROLLER) - const unsigned short EG_PIVC_P_GAIN = 1; - const unsigned short EG_PIVC_I_GAIN = 2; - const unsigned short EG_PIVC_FEED_FORWARD_VELOCITY_GAIN = 10; - const unsigned short EG_PIVC_FEED_FORWARD_ACCELERATION_GAIN = 11; - - // EGain (EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER) - const unsigned short EG_PIVCWO_P_GAIN = 1; - const unsigned short EG_PIVCWO_I_GAIN = 2; - const unsigned short EG_PIVCWO_FEED_FORWARD_VELOCITY_GAIN = 10; - const unsigned short EG_PIVCWO_FEED_FORWARD_ACCELERATION_GAIN = 11; - const unsigned short EG_PIVCWO_OBSERVER_THETA_GAIN = 20; - const unsigned short EG_PIVCWO_OBSERVER_OMEGA_GAIN = 21; - const unsigned short EG_PIVCWO_OBSERVER_TAU_GAIN = 22; - - // EGain (EC_PID_POSITION_CONTROLLER) - const unsigned short EG_PIDPC_P_GAIN = 1; - const unsigned short EG_PIDPC_I_GAIN = 2; - const unsigned short EG_PIDPC_D_GAIN = 3; - const unsigned short EG_PIDPC_FEED_FORWARD_VELOCITY_GAIN = 10; - const unsigned short EG_PIDPC_FEED_FORWARD_ACCELERATION_GAIN = 11; - - // EGain (EC_DUAL_LOOP_POSITION_CONTROLLER) - const unsigned short EG_DLPC_AUXILIARY_LOOP_P_GAIN = 1; - const unsigned short EG_DLPC_AUXILIARY_LOOP_I_GAIN = 2; - const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_VELOCITY_GAIN = 10; - const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_ACCELERATION_GAIN = 11; - const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_THETA_GAIN = 20; - const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_OMEGA_GAIN = 21; - const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_TAU_GAIN = 22; - const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_LOW = 101; - const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_HIGH = 102; - const unsigned short EG_DLPC_MAIN_LOOP_GAIN_SCHEDULING_WEIGHT = 110; - const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_A = 120; - const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_B = 121; - const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_C = 122; - const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_D = 123; - const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_E = 124; +// EController +extern const unsigned short EC_PI_CURRENT_CONTROLLER; //= 1; +extern const unsigned short EC_PI_VELOCITY_CONTROLLER; //= 10; +extern const unsigned short EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER; //= 11; +extern const unsigned short EC_PID_POSITION_CONTROLLER; //= 20; +extern const unsigned short EC_DUAL_LOOP_POSITION_CONTROLLER; //= 21; + +// EGain (EC_PI_CURRENT_CONTROLLER) +extern const unsigned short EG_PICC_P_GAIN; //= 1; +extern const unsigned short EG_PICC_I_GAIN; //= 2; + +// EGain (EC_PI_VELOCITY_CONTROLLER) +extern const unsigned short EG_PIVC_P_GAIN; //= 1; +extern const unsigned short EG_PIVC_I_GAIN; //= 2; +extern const unsigned short EG_PIVC_FEED_FORWARD_VELOCITY_GAIN; //= 10; +extern const unsigned short EG_PIVC_FEED_FORWARD_ACCELERATION_GAIN; //= 11; + +// EGain (EC_PI_VELOCITY_CONTROLLER_WITH_OBSERVER) +extern const unsigned short EG_PIVCWO_P_GAIN; //= 1; +extern const unsigned short EG_PIVCWO_I_GAIN; //= 2; +extern const unsigned short EG_PIVCWO_FEED_FORWARD_VELOCITY_GAIN; //= 10; +extern const unsigned short EG_PIVCWO_FEED_FORWARD_ACCELERATION_GAIN; //= 11; +extern const unsigned short EG_PIVCWO_OBSERVER_THETA_GAIN; //= 20; +extern const unsigned short EG_PIVCWO_OBSERVER_OMEGA_GAIN; //= 21; +extern const unsigned short EG_PIVCWO_OBSERVER_TAU_GAIN; //= 22; + +// EGain (EC_PID_POSITION_CONTROLLER) +extern const unsigned short EG_PIDPC_P_GAIN; //= 1; +extern const unsigned short EG_PIDPC_I_GAIN; //= 2; +extern const unsigned short EG_PIDPC_D_GAIN; //= 3; +extern const unsigned short EG_PIDPC_FEED_FORWARD_VELOCITY_GAIN; //= 10; +extern const unsigned short EG_PIDPC_FEED_FORWARD_ACCELERATION_GAIN; //= 11; + +// EGain (EC_DUAL_LOOP_POSITION_CONTROLLER) +extern const unsigned short EG_DLPC_AUXILIARY_LOOP_P_GAIN; //= 1; +extern const unsigned short EG_DLPC_AUXILIARY_LOOP_I_GAIN; //= 2; +extern const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_VELOCITY_GAIN; //= 10; +extern const unsigned short EG_DLPC_AUXILIARY_LOOP_FEED_FORWARD_ACCELERATION_GAIN; //= 11; +extern const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_THETA_GAIN; //= 20; +extern const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_OMEGA_GAIN; //= 21; +extern const unsigned short EG_DLPC_AUXILIARY_LOOP_OBSERVER_TAU_GAIN; //= 22; +extern const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_LOW; //= 101; +extern const unsigned short EG_DLPC_MAIN_LOOP_P_GAIN_HIGH; //= 102; +extern const unsigned short EG_DLPC_MAIN_LOOP_GAIN_SCHEDULING_WEIGHT; //= 110; +extern const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_A; //= 120; +extern const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_B; //= 121; +extern const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_C; //= 122; +extern const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_D; //= 123; +extern const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_E; //= 124; #ifdef __cplusplus -} // export "C" +} // extern "C" #endif diff --git a/epos2/epos2.c b/epos2/epos2.c index bdb4e70..489787d 100644 --- a/epos2/epos2.c +++ b/epos2/epos2.c @@ -1,61 +1,3 @@ -#include -#include - -#include "definitions.h" #include "epos2.h" -unsigned int InitializeDevice(struct Controller* controller, void* device_handle) { - unsigned int error_code; - int ret; - - device_handle = VCS_OpenDevice(controller->Name, - controller->Protocol, - controller->Interface, - controller->Port, - &error_code); - - if (device_handle == 0 && error_code != 0) { - printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); - return error_code; - }; - - ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); - - return (ret == 0 && error_code == 0) ? 0 : error_code; -} - -unsigned int AcquireDeviceInformation(struct Controller* controller_out, int flags) { - unsigned int error_code = 0; - int success; - int selection_end; - - if (flags & (1 << 2)) { memset(controller_out, 0, sizeof(*controller_out)); } - - if (flags & (1 << 1)) { - strncpy(controller_out->Name, "EPOS2", 6); - strncpy(controller_out->Protocol, "CANopen", 8); - } - - success = VCS_GetInterfaceNameSelection( - controller_out->Name, controller_out->Protocol, 1, - controller_out->Interface, 64, &selection_end, &error_code); - - return (success == 0 && error_code == 0) ? 0 : error_code; -} - -unsigned int CloseDevice(struct Controller* controller, void* device_handle) { - unsigned int error_code; - int ret; - - ret = VCS_CloseDevice(device_handle, &error_code); - - return (ret == 0 && error_code == 0) ? 0 : error_code; -} - -void PrintControllerCharacteristics(struct Controller* controller) { - printf("- Name: %s\n", controller->Name); - printf("- Node: %i\n", controller->NodeId); - printf("- Protocol: %s\n", controller->Protocol); - printf("- Interface: %s\n", controller->Interface); - printf("- Interface: %s\n", controller->Interface); -} +const char* DEFAULT_NAME = "EPOS2"; diff --git a/epos2/epos2.h b/epos2/epos2.h index ea01b16..3d71909 100644 --- a/epos2/epos2.h +++ b/epos2/epos2.h @@ -1,53 +1,16 @@ #pragma once +#include "libtestrig_api.h" +#include "controller.h" +#include "identify.h" +#include "connect.h" + #ifdef __cplusplus namespace VSCL::Rig { extern "C" { #endif // __cplusplus -#include "libtestrig_api.h" - -struct Controller { - char Name[8]; - char Protocol[16]; - char Interface[64]; - char Port[8]; - unsigned short NodeId; -}; - -enum ACQUIRE_DEVICE_INFORMATION_FLAGS { - FLAG_INIT_DEFAULTS = 1, - FLAG_ZERO_INIT = 2 -}; - -/* - * Populates the fields of the Controller information struct. - * - * Flags are passed bitwise ORed. - */ -unsigned int TESTRIG_API AcquireDeviceInformation(struct Controller* controller, int flags); - -/* - * - */ -unsigned int TESTRIG_API AcquireThreeDeviceInformations(struct Controller* controller, int flags); - -/* - * Initializes the device and sets its state for a clean init. - * - * Refer to Page 162 of the manual. - */ -unsigned int TESTRIG_API InitializeDevice(struct Controller* controller, void* device_handle); - -/* - * Closes all connections to the controller - */ -unsigned int TESTRIG_API CloseDevice(struct Controller* controller, void* device_handle); - -/* - * Print out controller characteristics. - */ -void TESTRIG_API PrintControllerCharacteristics(struct Controller* controller); +extern const char* DEFAULT_NAME; #ifdef __cplusplus } // extern "C" diff --git a/epos2/identify.c b/epos2/identify.c new file mode 100644 index 0000000..a3d4df4 --- /dev/null +++ b/epos2/identify.c @@ -0,0 +1,32 @@ +#include +#include + +#include "controller.h" +#include "definitions.h" +#include "identify.h" + +unsigned int AcquireDeviceInformation(struct Controller* controller_out, int flags) { + unsigned int error_code = 0; + int success; + int selection_end; + + if (flags & (1 << 2)) { memset(controller_out, 0, sizeof(*controller_out)); } + + if (flags & (1 << 1)) { + strncpy(controller_out->Name, "EPOS2", 6); + strncpy(controller_out->Protocol, "CANopen", 8); + } + + success = VCS_GetInterfaceNameSelection( + controller_out->Name, controller_out->Protocol, 1, + controller_out->Interface, 64, &selection_end, &error_code); + + return (success == 0 && error_code == 0) ? 0 : error_code; +} + +void PrintControllerCharacteristics(struct Controller* controller) { + printf("- Name: %s\n", controller->Name); + printf("- Node: %i\n", controller->NodeId); + printf("- Protocol: %s\n", controller->Protocol); + printf("- Interface: %s\n", controller->Interface); +} diff --git a/epos2/identify.h b/epos2/identify.h new file mode 100644 index 0000000..51fcfb3 --- /dev/null +++ b/epos2/identify.h @@ -0,0 +1,35 @@ +#pragma once + +#include "libtestrig_api.h" +#include "controller.h" + +#ifdef __cplusplus +namespace VSCL::Rig { +extern "C" { +#endif // __cplusplus + +/* + * @brief Populates the fields of the Controller information struct. + * + * Flags are passed bitwise ORed. + * + * Refer to Page 162 of the manual under HELP, + * which describes several of the functions wrapped here. + */ +unsigned int TESTRIG_API AcquireDeviceInformation(struct Controller* controller, int flags); + +/* + * @brief Acquire the three controllers. + */ +unsigned int TESTRIG_API AcquireThreeDeviceInformations(struct Controller** controllers, int flags); + +/* + * @brief Print out controller characteristics. + */ +void TESTRIG_API PrintControllerCharacteristics(struct Controller* controller); + + +#ifdef __cplusplus +} // extern "C" +} // namespace VSCL::Rig +#endif // __cplusplus diff --git a/epos2/meson.build b/epos2/meson.build index 73a034d..639a765 100644 --- a/epos2/meson.build +++ b/epos2/meson.build @@ -24,7 +24,8 @@ elif (operating_system == 'linux') required: false), ) - epos2_srcs = [ './epos2/constants.c', './epos2/epos2.c' ] + epos2_srcs = [ './epos2/epos2.c', './epos2/definitions.c', + './epos2/identify.c', './epos2/connect.c' ] # Others else From 2a3e4dce035d1f88b2567f6d04345f7ab6527918 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Thu, 19 Mar 2026 18:42:08 -0500 Subject: [PATCH 16/37] It acquires only the first device --- epos2/connect.c | 14 +++++++++----- epos2/controller.h | 2 +- epos2/identify.c | 25 +++++++++++++++++++++---- epos2/identify.h | 7 ++++--- 4 files changed, 35 insertions(+), 13 deletions(-) diff --git a/epos2/connect.c b/epos2/connect.c index fd2ed18..4ef3d03 100644 --- a/epos2/connect.c +++ b/epos2/connect.c @@ -1,7 +1,8 @@ #include -#include "definitions.h" #include "connect.h" +#include "definitions.h" +#include "identify.h" unsigned int InitializeDevice(struct Controller* controller, void* device_handle) { unsigned int error_code; @@ -14,14 +15,16 @@ unsigned int InitializeDevice(struct Controller* controller, void* device_handle &error_code); if (device_handle == 0 && error_code != 0) { - printf("ERROR %uix: Failed to open device with with following characteristics:\n", - error_code); + printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); + PrintControllerCharacteristics(controller); + return error_code; }; ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); - return (ret == 0 && error_code == 0) ? 0 : error_code; + controller->State = CTRL_STATE_OPENED; + return (ret != 0 && error_code == 0) ? 0 : error_code; } // uint Open unsigned int CloseDevice(struct Controller* controller, void* device_handle) { @@ -29,7 +32,8 @@ unsigned int CloseDevice(struct Controller* controller, void* device_handle) { int ret; ret = VCS_CloseDevice(device_handle, &error_code); + controller->State = CTRL_STATE_CLOSED; - return (ret == 0 && error_code == 0) ? 0 : error_code; + return (ret != 0 && error_code == 0) ? 0 : error_code; } diff --git a/epos2/controller.h b/epos2/controller.h index 2872b72..f5633a4 100644 --- a/epos2/controller.h +++ b/epos2/controller.h @@ -7,7 +7,7 @@ extern "C" { enum ACQUIRE_DEVICE_INFORMATION_FLAGS { FLAG_INIT_DEFAULTS = 1, - FLAG_ZERO_INIT = 2 + FLAG_ZERO_INIT = 2, }; enum ControllerState { diff --git a/epos2/identify.c b/epos2/identify.c index a3d4df4..39b2d44 100644 --- a/epos2/identify.c +++ b/epos2/identify.c @@ -5,9 +5,8 @@ #include "definitions.h" #include "identify.h" -unsigned int AcquireDeviceInformation(struct Controller* controller_out, int flags) { +unsigned int AcquireFirstDeviceInformation(struct Controller* controller_out, int flags) { unsigned int error_code = 0; - int success; int selection_end; if (flags & (1 << 2)) { memset(controller_out, 0, sizeof(*controller_out)); } @@ -16,12 +15,30 @@ unsigned int AcquireDeviceInformation(struct Controller* controller_out, int fla strncpy(controller_out->Name, "EPOS2", 6); strncpy(controller_out->Protocol, "CANopen", 8); } + else { + int name_found = VCS_GetDeviceNameSelection( + 1, controller_out->Name, 8, + &selection_end, &error_code); + if (name_found == 0) { return error_code; } - success = VCS_GetInterfaceNameSelection( + int protocol_found = VCS_GetProtocolStackNameSelection( + controller_out->Name, 1, + controller_out->Protocol, 16, + &selection_end, &error_code); + if (protocol_found == 0) { return error_code; } + } + + int interface_found = VCS_GetInterfaceNameSelection( controller_out->Name, controller_out->Protocol, 1, controller_out->Interface, 64, &selection_end, &error_code); + if (interface_found == 0) { return error_code; } + + int port_found = VCS_GetPortNameSelection( + controller_out->Name, controller_out->Protocol, controller_out->Interface, 1, + controller_out->Port, 8, &selection_end, &error_code); + if (port_found == 0) { return error_code; } - return (success == 0 && error_code == 0) ? 0 : error_code; + return 0; } void PrintControllerCharacteristics(struct Controller* controller) { diff --git a/epos2/identify.h b/epos2/identify.h index 51fcfb3..771893a 100644 --- a/epos2/identify.h +++ b/epos2/identify.h @@ -10,23 +10,24 @@ extern "C" { /* * @brief Populates the fields of the Controller information struct. + * This only operates on the first controller that the Command Library finds. * * Flags are passed bitwise ORed. * * Refer to Page 162 of the manual under HELP, * which describes several of the functions wrapped here. */ -unsigned int TESTRIG_API AcquireDeviceInformation(struct Controller* controller, int flags); +unsigned int TESTRIG_API AcquireFirstDeviceInformation(struct Controller* controller_out, int flags); /* * @brief Acquire the three controllers. */ -unsigned int TESTRIG_API AcquireThreeDeviceInformations(struct Controller** controllers, int flags); +unsigned int TESTRIG_API AcquireThreeDeviceInformations(struct Controller** controllers_out, int flags); /* * @brief Print out controller characteristics. */ -void TESTRIG_API PrintControllerCharacteristics(struct Controller* controller); +void TESTRIG_API PrintControllerCharacteristics(struct Controller* controller_out); #ifdef __cplusplus From 4c5daf447cf55e4ab7a56160087a10f7c90f37d3 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Thu, 19 Mar 2026 18:58:23 -0500 Subject: [PATCH 17/37] Actually i should make these discrete things --- epos2/identify.c | 93 +++++++++++++++++++++++++++++++++++++++++++++--- epos2/identify.h | 32 +++++++++++++++++ 2 files changed, 120 insertions(+), 5 deletions(-) diff --git a/epos2/identify.c b/epos2/identify.c index 39b2d44..b2008a8 100644 --- a/epos2/identify.c +++ b/epos2/identify.c @@ -28,17 +28,100 @@ unsigned int AcquireFirstDeviceInformation(struct Controller* controller_out, in if (protocol_found == 0) { return error_code; } } + return 0; +} + +unsigned int AcquireDeviceNames(struct Controller** controllers_out, int size) { + int n = 0; + unsigned int error_code = 0; + int selection_end; + + int name_found = VCS_GetDeviceNameSelection( + 1, controllers_out[0]->Name, 8, + &selection_end, &error_code); + if (name_found != 0) { return error_code; } + n++; + + while (!selection_end && n < size) { + name_found = VCS_GetDeviceNameSelection( + 0, controllers_out[n]->Name, 8, + &selection_end, &error_code); + + if (name_found != 0) { return error_code; } + n++; + } + + return error_code; +} + +unsigned int AcquireDeviceProtocols(struct Controller** controllers_out, int size) { + int n = 0; + unsigned int error_code = 0; + int selection_end; + + int protocol_found = VCS_GetProtocolStackNameSelection( + controllers_out[0]->Name, 1, + controllers_out[0]->Protocol, 16, + &selection_end, &error_code); + if (protocol_found == 0) { return error_code; } + n++; + + while (!selection_end && n < size) { + protocol_found = VCS_GetProtocolStackNameSelection( + controllers_out[n]->Name, 0, + controllers_out[n]->Protocol, 16, + &selection_end, &error_code); + + if (protocol_found == 0) { return error_code; } + n++; + } + + return error_code; +} + +unsigned int AcquireDeviceInterfaces(struct Controller** controllers_out, int size) { + int n = 0; + unsigned int error_code = 0; + int selection_end; + int interface_found = VCS_GetInterfaceNameSelection( - controller_out->Name, controller_out->Protocol, 1, - controller_out->Interface, 64, &selection_end, &error_code); + controllers_out[0]->Name, controllers_out[0]->Protocol, 1, + controllers_out[0]->Interface, 64, &selection_end, &error_code); if (interface_found == 0) { return error_code; } + n++; + + while (!selection_end && n < size) { + interface_found = VCS_GetInterfaceNameSelection( + controllers_out[n]->Name, controllers_out[n]->Protocol, 0, + controllers_out[n]->Interface, 64, &selection_end, &error_code); + + if (interface_found == 0) { return error_code; } + n++; + } + + return error_code; +} + +unsigned int AcquireDevicePorts(struct Controller** controllers_out, int size) { + int n = 0; + unsigned int error_code = 0; + int selection_end; int port_found = VCS_GetPortNameSelection( - controller_out->Name, controller_out->Protocol, controller_out->Interface, 1, - controller_out->Port, 8, &selection_end, &error_code); + controllers_out[0]->Name, controllers_out[0]->Protocol, controllers_out[0]->Interface, 1, + controllers_out[0]->Port, 8, &selection_end, &error_code); if (port_found == 0) { return error_code; } + n++; - return 0; + while (!selection_end && n < size) { + port_found = VCS_GetPortNameSelection( + controllers_out[n]->Name, controllers_out[n]->Protocol, controllers_out[n]->Interface, 0, + controllers_out[n]->Port, 8, &selection_end, &error_code); + if (port_found == 0) { return error_code; } + n++; + } + + return error_code; } void PrintControllerCharacteristics(struct Controller* controller) { diff --git a/epos2/identify.h b/epos2/identify.h index 771893a..3ed594b 100644 --- a/epos2/identify.h +++ b/epos2/identify.h @@ -19,6 +19,38 @@ extern "C" { */ unsigned int TESTRIG_API AcquireFirstDeviceInformation(struct Controller* controller_out, int flags); +/* + * @brief Finds the name of the Controllers in the array. + * This operates on all connected controllers. + * + * Refer to Page 3-25 of the manual. + */ +unsigned int TESTRIG_API AcquireDeviceNames(struct Controller** controllers_out, int size); + +/* + * @brief Finds the protocol stacks of the Controller in the array. + * This operates on all connected controllers. + * + * Refer to Page 3-26 of the manual. + */ +unsigned int TESTRIG_API AcquireDeviceProtocols(struct Controller** controllers_out, int size); + +/* + * @brief Finds the interfaces of the Controller in the array. + * This operates on all connected controllers. + * + * Refer to Page 3-27 of the manual. + */ +unsigned int TESTRIG_API AcquireDeviceInterfaces(struct Controller** controllers_out, int size); + +/* + * @brief Finds the ports of the Controller in the array. + * This operates on all connected controllers. + * + * Refer to Page 3-28 of the manual. + */ +unsigned int TESTRIG_API AcquireDevicePorts(struct Controller** controllers_out, int size); + /* * @brief Acquire the three controllers. */ From 3817959513f9a820e6f97f664cc2b2a3e965c2c9 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Thu, 19 Mar 2026 19:05:40 -0500 Subject: [PATCH 18/37] Proper device identifiers --- epos2/identify.c | 54 +++++++++++++++++++++++++----------------------- epos2/identify.h | 15 ++------------ 2 files changed, 30 insertions(+), 39 deletions(-) diff --git a/epos2/identify.c b/epos2/identify.c index b2008a8..beefa61 100644 --- a/epos2/identify.c +++ b/epos2/identify.c @@ -5,32 +5,6 @@ #include "definitions.h" #include "identify.h" -unsigned int AcquireFirstDeviceInformation(struct Controller* controller_out, int flags) { - unsigned int error_code = 0; - int selection_end; - - if (flags & (1 << 2)) { memset(controller_out, 0, sizeof(*controller_out)); } - - if (flags & (1 << 1)) { - strncpy(controller_out->Name, "EPOS2", 6); - strncpy(controller_out->Protocol, "CANopen", 8); - } - else { - int name_found = VCS_GetDeviceNameSelection( - 1, controller_out->Name, 8, - &selection_end, &error_code); - if (name_found == 0) { return error_code; } - - int protocol_found = VCS_GetProtocolStackNameSelection( - controller_out->Name, 1, - controller_out->Protocol, 16, - &selection_end, &error_code); - if (protocol_found == 0) { return error_code; } - } - - return 0; -} - unsigned int AcquireDeviceNames(struct Controller** controllers_out, int size) { int n = 0; unsigned int error_code = 0; @@ -124,6 +98,34 @@ unsigned int AcquireDevicePorts(struct Controller** controllers_out, int size) { return error_code; } +unsigned int AcquireDeviceInfo(struct Controller** controllers_out, int size, int flags) { + unsigned int error_code = 0; + + if (flags & (1 << 2)) { memset(controllers_out, 0, sizeof(*controllers_out)); } + + if (flags & (1 << 1)) { + for (int i = 0; i < size; i++) { + strncpy(controllers_out[i]->Name, "EPOS2", 6); + strncpy(controllers_out[i]->Protocol, "CANopen", 8); + } + } + else { + error_code = AcquireDeviceNames(controllers_out, size); + if (error_code != 0) { return error_code; }; + + error_code = AcquireDeviceProtocols(controllers_out, size); + if (error_code != 0) { return error_code; }; + } + + error_code = AcquireDeviceInterfaces(controllers_out, size); + if (error_code != 0) { return error_code; } + + error_code = AcquireDevicePorts(controllers_out, size); + if (error_code != 0) { return error_code; } + + return 0; +} + void PrintControllerCharacteristics(struct Controller* controller) { printf("- Name: %s\n", controller->Name); printf("- Node: %i\n", controller->NodeId); diff --git a/epos2/identify.h b/epos2/identify.h index 3ed594b..4c24eb7 100644 --- a/epos2/identify.h +++ b/epos2/identify.h @@ -8,17 +8,6 @@ namespace VSCL::Rig { extern "C" { #endif // __cplusplus -/* - * @brief Populates the fields of the Controller information struct. - * This only operates on the first controller that the Command Library finds. - * - * Flags are passed bitwise ORed. - * - * Refer to Page 162 of the manual under HELP, - * which describes several of the functions wrapped here. - */ -unsigned int TESTRIG_API AcquireFirstDeviceInformation(struct Controller* controller_out, int flags); - /* * @brief Finds the name of the Controllers in the array. * This operates on all connected controllers. @@ -52,9 +41,9 @@ unsigned int TESTRIG_API AcquireDeviceInterfaces(struct Controller** controllers unsigned int TESTRIG_API AcquireDevicePorts(struct Controller** controllers_out, int size); /* - * @brief Acquire the three controllers. + * @brief Acquire the information on the set number of controllers. */ -unsigned int TESTRIG_API AcquireThreeDeviceInformations(struct Controller** controllers_out, int flags); +unsigned int TESTRIG_API AcquireDeviceInfo(struct Controller** controllers_out, int size, int flags); /* * @brief Print out controller characteristics. From a13a1801ce3e193f3b3d19e865fe5eaa9e098571 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Thu, 19 Mar 2026 19:33:35 -0500 Subject: [PATCH 19/37] Node set --- epos2/controller.h | 9 ++++++++- epos2/identify.c | 35 +++++++++++++++++++++++++---------- epos2/identify.h | 23 ++++++++++++++++++----- 3 files changed, 51 insertions(+), 16 deletions(-) diff --git a/epos2/controller.h b/epos2/controller.h index f5633a4..e15145d 100644 --- a/epos2/controller.h +++ b/epos2/controller.h @@ -1,6 +1,13 @@ #pragma once #ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +#include + +#ifdef __cplusplus +} // extern "C" (headers) namespace VSCL::Rig { extern "C" { #endif // __cplusplus @@ -30,7 +37,7 @@ struct Controller { // The name of the port used in connection. char Port[8]; // The node of the controller. - unsigned short NodeId; + uint8_t NodeId; // State of the controller. enum ControllerState State; }; diff --git a/epos2/identify.c b/epos2/identify.c index beefa61..3fbc660 100644 --- a/epos2/identify.c +++ b/epos2/identify.c @@ -5,9 +5,9 @@ #include "definitions.h" #include "identify.h" -unsigned int AcquireDeviceNames(struct Controller** controllers_out, int size) { +uint32_t AcquireDeviceNames(struct Controller** controllers_out, int size) { + uint32_t error_code = 0; int n = 0; - unsigned int error_code = 0; int selection_end; int name_found = VCS_GetDeviceNameSelection( @@ -28,9 +28,9 @@ unsigned int AcquireDeviceNames(struct Controller** controllers_out, int size) { return error_code; } -unsigned int AcquireDeviceProtocols(struct Controller** controllers_out, int size) { +uint32_t AcquireDeviceProtocols(struct Controller** controllers_out, int size) { + uint32_t error_code = 0; int n = 0; - unsigned int error_code = 0; int selection_end; int protocol_found = VCS_GetProtocolStackNameSelection( @@ -53,9 +53,9 @@ unsigned int AcquireDeviceProtocols(struct Controller** controllers_out, int siz return error_code; } -unsigned int AcquireDeviceInterfaces(struct Controller** controllers_out, int size) { +uint32_t AcquireDeviceInterfaces(struct Controller** controllers_out, int size) { + uint32_t error_code = 0; int n = 0; - unsigned int error_code = 0; int selection_end; int interface_found = VCS_GetInterfaceNameSelection( @@ -76,9 +76,9 @@ unsigned int AcquireDeviceInterfaces(struct Controller** controllers_out, int si return error_code; } -unsigned int AcquireDevicePorts(struct Controller** controllers_out, int size) { +uint32_t AcquireDevicePorts(struct Controller** controllers_out, int size) { + uint32_t error_code = 0; int n = 0; - unsigned int error_code = 0; int selection_end; int port_found = VCS_GetPortNameSelection( @@ -98,8 +98,8 @@ unsigned int AcquireDevicePorts(struct Controller** controllers_out, int size) { return error_code; } -unsigned int AcquireDeviceInfo(struct Controller** controllers_out, int size, int flags) { - unsigned int error_code = 0; +uint32_t AcquireDeviceInfos(struct Controller** controllers_out, int size, int flags) { + uint32_t error_code = 0; if (flags & (1 << 2)) { memset(controllers_out, 0, sizeof(*controllers_out)); } @@ -125,6 +125,21 @@ unsigned int AcquireDeviceInfo(struct Controller** controllers_out, int size, in return 0; } +uint32_t SetDeviceNode(struct Controller* controller_out, void* handle, uint8_t new_node) { + uint32_t error_code = 0; + uint32_t bytes_written = 0; + int ret; + + ret = VCS_SetObject( + handle, 0, + 0x2000, 0x00, + &new_node, 1, + &bytes_written, &error_code); + + if (ret != 0) { controller_out->NodeId = new_node; } + + return error_code; +} void PrintControllerCharacteristics(struct Controller* controller) { printf("- Name: %s\n", controller->Name); diff --git a/epos2/identify.h b/epos2/identify.h index 4c24eb7..040550e 100644 --- a/epos2/identify.h +++ b/epos2/identify.h @@ -1,9 +1,15 @@ #pragma once +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +#include #include "libtestrig_api.h" #include "controller.h" #ifdef __cplusplus +} // extern "C" (headers) namespace VSCL::Rig { extern "C" { #endif // __cplusplus @@ -14,7 +20,7 @@ extern "C" { * * Refer to Page 3-25 of the manual. */ -unsigned int TESTRIG_API AcquireDeviceNames(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDeviceNames(struct Controller** controllers_out, int size); /* * @brief Finds the protocol stacks of the Controller in the array. @@ -22,7 +28,7 @@ unsigned int TESTRIG_API AcquireDeviceNames(struct Controller** controllers_out, * * Refer to Page 3-26 of the manual. */ -unsigned int TESTRIG_API AcquireDeviceProtocols(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDeviceProtocols(struct Controller** controllers_out, int size); /* * @brief Finds the interfaces of the Controller in the array. @@ -30,7 +36,7 @@ unsigned int TESTRIG_API AcquireDeviceProtocols(struct Controller** controllers_ * * Refer to Page 3-27 of the manual. */ -unsigned int TESTRIG_API AcquireDeviceInterfaces(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDeviceInterfaces(struct Controller** controllers_out, int size); /* * @brief Finds the ports of the Controller in the array. @@ -38,12 +44,19 @@ unsigned int TESTRIG_API AcquireDeviceInterfaces(struct Controller** controllers * * Refer to Page 3-28 of the manual. */ -unsigned int TESTRIG_API AcquireDevicePorts(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDevicePorts(struct Controller** controllers_out, int size); /* * @brief Acquire the information on the set number of controllers. */ -unsigned int TESTRIG_API AcquireDeviceInfo(struct Controller** controllers_out, int size, int flags); +uint32_t TESTRIG_API AcquireDeviceInfos(struct Controller** controllers_out, int size, int flags); + +/* + * @brief Set the controller to be identified by the given node on the network. + * + * Refer to 8-135 of the firmware manual. An unconfigured node is found at node 0. + */ +uint32_t TESTRIG_API SetDeviceNode(struct Controller* controller_out, void* handle, uint8_t new_node); /* * @brief Print out controller characteristics. From 707f8806451a18a3ad03128acab03a9d4e03501a Mon Sep 17 00:00:00 2001 From: JC Luna Date: Thu, 19 Mar 2026 19:40:31 -0500 Subject: [PATCH 20/37] Set enable/disable states --- epos2/connect.c | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/epos2/connect.c b/epos2/connect.c index 4ef3d03..92195c3 100644 --- a/epos2/connect.c +++ b/epos2/connect.c @@ -22,9 +22,11 @@ unsigned int InitializeDevice(struct Controller* controller, void* device_handle }; ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); + if (ret == 0) { return error_code; } + ret = VCS_SetEnableState(device_handle, controller->NodeId, &error_code); controller->State = CTRL_STATE_OPENED; - return (ret != 0 && error_code == 0) ? 0 : error_code; + return error_code; } // uint Open unsigned int CloseDevice(struct Controller* controller, void* device_handle) { @@ -32,8 +34,10 @@ unsigned int CloseDevice(struct Controller* controller, void* device_handle) { int ret; ret = VCS_CloseDevice(device_handle, &error_code); - controller->State = CTRL_STATE_CLOSED; + if (ret == 0) { return error_code; } - return (ret != 0 && error_code == 0) ? 0 : error_code; + ret = VCS_SetDisableState(device_handle, controller->NodeId, &error_code); + controller->State = CTRL_STATE_CLOSED; + return error_code; } From 6ea658e8833ee022a9d85c5b3367aa9db737b804 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Thu, 19 Mar 2026 20:44:12 -0500 Subject: [PATCH 21/37] Gateway topology subdevice functions --- epos2/connect.c | 70 +++++++++++++++++++++++++++++++++++----------- epos2/connect.h | 17 ++++++++--- epos2/controller.h | 5 ---- epos2/identify.c | 13 +++++---- epos2/identify.h | 7 ++++- 5 files changed, 80 insertions(+), 32 deletions(-) diff --git a/epos2/connect.c b/epos2/connect.c index 92195c3..888c44a 100644 --- a/epos2/connect.c +++ b/epos2/connect.c @@ -4,33 +4,71 @@ #include "definitions.h" #include "identify.h" -unsigned int InitializeDevice(struct Controller* controller, void* device_handle) { - unsigned int error_code; +uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle) { + uint32_t error_code = 0; int ret; - device_handle = VCS_OpenDevice(controller->Name, - controller->Protocol, - controller->Interface, - controller->Port, - &error_code); + ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); + if (ret == 0) { return error_code; } + + ret = VCS_SetEnableState(device_handle, controller->NodeId, &error_code); + controller->State = CTRL_STATE_OPENED; + return error_code; +} - if (device_handle == 0 && error_code != 0) { +uint32_t InitializeDevices(struct Controller** controllers_out, void* node_1, void* node_2, void* node_3) { + uint32_t error_code = 0; + + node_1 = VCS_OpenDevice(controllers_out[0]->Name, + controllers_out[0]->Protocol, + controllers_out[0]->Interface, + controllers_out[0]->Port, + &error_code); + + controllers_out[0]->NodeId = 1; + + if (node_1 == 0 || error_code != 0) { printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); - PrintControllerCharacteristics(controller); + PrintControllerCharacteristics(controllers_out[0]); + return error_code; + }; + + CleanEnableDevice(controllers_out[0], node_1); + + node_2 = VCS_OpenSubDevice(node_1, + controllers_out[1]->Name, + controllers_out[1]->Protocol, + &error_code); + controllers_out[1]->NodeId = 2; + + if (node_2 == 0 || error_code != 0) { + printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); + PrintControllerCharacteristics(controllers_out[1]); return error_code; }; - ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); - if (ret == 0) { return error_code; } + CleanEnableDevice(controllers_out[1], node_2); - ret = VCS_SetEnableState(device_handle, controller->NodeId, &error_code); - controller->State = CTRL_STATE_OPENED; - return error_code; + node_3 = VCS_OpenSubDevice(node_2, + controllers_out[2]->Name, + controllers_out[2]->Protocol, + &error_code); + + if (node_3 == 0 || error_code != 0) { + printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); + PrintControllerCharacteristics(controllers_out[2]); + return error_code; + }; + + controllers_out[2]->NodeId = 3; + + CleanEnableDevice(controllers_out[2], node_2); + return 0; } // uint Open -unsigned int CloseDevice(struct Controller* controller, void* device_handle) { - unsigned int error_code; +uint32_t CloseDevice(struct Controller* controller, void* device_handle) { + uint32_t error_code = 0; int ret; ret = VCS_CloseDevice(device_handle, &error_code); diff --git a/epos2/connect.h b/epos2/connect.h index 21da9e7..c0ce3f2 100644 --- a/epos2/connect.h +++ b/epos2/connect.h @@ -1,20 +1,29 @@ #pragma once #ifdef __cplusplus -namespace VSCL::Rig { extern "C" { -#endif // __cplusplus +#endif + +#include #include "libtestrig_api.h" #include "controller.h" +#ifdef __cplusplus +} // extern "C" (headers) +namespace VSCL::Rig { +extern "C" { +#endif // __cplusplus + +uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle); + /* * @brief Opens communication to the device and sets its state for a clean init. * * Refer to Page 162 of the manual under INITIALIZATION, * which describes several of the methods wrapped here. */ -unsigned int TESTRIG_API InitializeDevice(struct Controller* controller, void* device_handle); +uint32_t TESTRIG_API InitializeDevices(struct Controller** controllers_out, void* node_1, void* node_2, void* node_3); /* * Closes all connections to the controller @@ -22,7 +31,7 @@ unsigned int TESTRIG_API InitializeDevice(struct Controller* controller, void* d * Refer to Page 162 of the manual under CLOSING PROCEDURE, * which describes several of the methods wrapped here. */ -unsigned int TESTRIG_API CloseDevice(struct Controller* controller, void* device_handle); +uint32_t TESTRIG_API CloseDevice(struct Controller* controller, void* device_handle); #ifdef __cplusplus } // extern "C" diff --git a/epos2/controller.h b/epos2/controller.h index e15145d..b1070ba 100644 --- a/epos2/controller.h +++ b/epos2/controller.h @@ -12,11 +12,6 @@ namespace VSCL::Rig { extern "C" { #endif // __cplusplus -enum ACQUIRE_DEVICE_INFORMATION_FLAGS { - FLAG_INIT_DEFAULTS = 1, - FLAG_ZERO_INIT = 2, -}; - enum ControllerState { CTRL_STATE_CLOSED = 1, CTRL_STATE_OPENED = 2, diff --git a/epos2/identify.c b/epos2/identify.c index 3fbc660..2ef970e 100644 --- a/epos2/identify.c +++ b/epos2/identify.c @@ -16,7 +16,7 @@ uint32_t AcquireDeviceNames(struct Controller** controllers_out, int size) { if (name_found != 0) { return error_code; } n++; - while (!selection_end && n < size) { + while (selection_end == 0 && n < size) { name_found = VCS_GetDeviceNameSelection( 0, controllers_out[n]->Name, 8, &selection_end, &error_code); @@ -40,7 +40,7 @@ uint32_t AcquireDeviceProtocols(struct Controller** controllers_out, int size) { if (protocol_found == 0) { return error_code; } n++; - while (!selection_end && n < size) { + while (selection_end == 0 && n < size) { protocol_found = VCS_GetProtocolStackNameSelection( controllers_out[n]->Name, 0, controllers_out[n]->Protocol, 16, @@ -64,7 +64,7 @@ uint32_t AcquireDeviceInterfaces(struct Controller** controllers_out, int size) if (interface_found == 0) { return error_code; } n++; - while (!selection_end && n < size) { + while (selection_end == 0 && n < size) { interface_found = VCS_GetInterfaceNameSelection( controllers_out[n]->Name, controllers_out[n]->Protocol, 0, controllers_out[n]->Interface, 64, &selection_end, &error_code); @@ -87,7 +87,7 @@ uint32_t AcquireDevicePorts(struct Controller** controllers_out, int size) { if (port_found == 0) { return error_code; } n++; - while (!selection_end && n < size) { + while (selection_end == 0 && n < size) { port_found = VCS_GetPortNameSelection( controllers_out[n]->Name, controllers_out[n]->Protocol, controllers_out[n]->Interface, 0, controllers_out[n]->Port, 8, &selection_end, &error_code); @@ -125,13 +125,14 @@ uint32_t AcquireDeviceInfos(struct Controller** controllers_out, int size, int f return 0; } -uint32_t SetDeviceNode(struct Controller* controller_out, void* handle, uint8_t new_node) { + +uint32_t SetDeviceNode(struct Controller* controller_out, void* handle, uint8_t old_node, uint8_t new_node) { uint32_t error_code = 0; uint32_t bytes_written = 0; int ret; ret = VCS_SetObject( - handle, 0, + handle, old_node, 0x2000, 0x00, &new_node, 1, &bytes_written, &error_code); diff --git a/epos2/identify.h b/epos2/identify.h index 040550e..2a6bf3c 100644 --- a/epos2/identify.h +++ b/epos2/identify.h @@ -14,6 +14,11 @@ namespace VSCL::Rig { extern "C" { #endif // __cplusplus +enum ACQUIRE_DEVICE_INFORMATION_FLAGS { + FLAG_ACQUIRE_INIT_DEFAULTS = 1, + FLAG_ACQUIRE_ZERO_INIT = 2, +}; + /* * @brief Finds the name of the Controllers in the array. * This operates on all connected controllers. @@ -56,7 +61,7 @@ uint32_t TESTRIG_API AcquireDeviceInfos(struct Controller** controllers_out, int * * Refer to 8-135 of the firmware manual. An unconfigured node is found at node 0. */ -uint32_t TESTRIG_API SetDeviceNode(struct Controller* controller_out, void* handle, uint8_t new_node); +uint32_t TESTRIG_API SetDeviceNode(struct Controller* controller_out, void* handle, uint8_t old_node, uint8_t new_node); /* * @brief Print out controller characteristics. From 51d302ab85223fe59baff7c6aaf179a006944f5e Mon Sep 17 00:00:00 2001 From: JC Luna Date: Sat, 21 Mar 2026 22:14:55 -0500 Subject: [PATCH 22/37] All files to lib dir --- {epos2 => lib/epos2}/LICENSE | 0 {epos2 => lib/epos2}/connect.c | 0 {epos2 => lib/epos2}/connect.h | 0 {epos2 => lib/epos2}/controller.h | 0 {epos2 => lib/epos2}/definitions.c | 0 {epos2 => lib/epos2}/definitions.h | 0 {epos2 => lib/epos2}/epos2.c | 0 {epos2 => lib/epos2}/epos2.h | 0 {epos2 => lib/epos2}/identify.c | 0 {epos2 => lib/epos2}/identify.h | 0 {epos2 => lib/epos2}/meson.build | 0 {ipc => lib/ipc}/LICENSE | 0 {ipc => lib/ipc}/constants.c | 0 {ipc => lib/ipc}/constants.h | 0 {ipc => lib/ipc}/ipc.c | 0 {ipc => lib/ipc}/ipc.h | 0 {ipc => lib/ipc}/meson.build | 0 {ipc => lib/ipc}/message.c | 0 {ipc => lib/ipc}/message.h | 0 {ipc => lib/ipc}/os.c | 0 {ipc => lib/ipc}/os.h | 0 libtestrig_api.h => lib/libtestrig_api.h | 0 lib/meson.build | 9 +++++++++ meson.build | 11 +---------- 24 files changed, 10 insertions(+), 10 deletions(-) rename {epos2 => lib/epos2}/LICENSE (100%) rename {epos2 => lib/epos2}/connect.c (100%) rename {epos2 => lib/epos2}/connect.h (100%) rename {epos2 => lib/epos2}/controller.h (100%) rename {epos2 => lib/epos2}/definitions.c (100%) rename {epos2 => lib/epos2}/definitions.h (100%) rename {epos2 => lib/epos2}/epos2.c (100%) rename {epos2 => lib/epos2}/epos2.h (100%) rename {epos2 => lib/epos2}/identify.c (100%) rename {epos2 => lib/epos2}/identify.h (100%) rename {epos2 => lib/epos2}/meson.build (100%) rename {ipc => lib/ipc}/LICENSE (100%) rename {ipc => lib/ipc}/constants.c (100%) rename {ipc => lib/ipc}/constants.h (100%) rename {ipc => lib/ipc}/ipc.c (100%) rename {ipc => lib/ipc}/ipc.h (100%) rename {ipc => lib/ipc}/meson.build (100%) rename {ipc => lib/ipc}/message.c (100%) rename {ipc => lib/ipc}/message.h (100%) rename {ipc => lib/ipc}/os.c (100%) rename {ipc => lib/ipc}/os.h (100%) rename libtestrig_api.h => lib/libtestrig_api.h (100%) create mode 100644 lib/meson.build diff --git a/epos2/LICENSE b/lib/epos2/LICENSE similarity index 100% rename from epos2/LICENSE rename to lib/epos2/LICENSE diff --git a/epos2/connect.c b/lib/epos2/connect.c similarity index 100% rename from epos2/connect.c rename to lib/epos2/connect.c diff --git a/epos2/connect.h b/lib/epos2/connect.h similarity index 100% rename from epos2/connect.h rename to lib/epos2/connect.h diff --git a/epos2/controller.h b/lib/epos2/controller.h similarity index 100% rename from epos2/controller.h rename to lib/epos2/controller.h diff --git a/epos2/definitions.c b/lib/epos2/definitions.c similarity index 100% rename from epos2/definitions.c rename to lib/epos2/definitions.c diff --git a/epos2/definitions.h b/lib/epos2/definitions.h similarity index 100% rename from epos2/definitions.h rename to lib/epos2/definitions.h diff --git a/epos2/epos2.c b/lib/epos2/epos2.c similarity index 100% rename from epos2/epos2.c rename to lib/epos2/epos2.c diff --git a/epos2/epos2.h b/lib/epos2/epos2.h similarity index 100% rename from epos2/epos2.h rename to lib/epos2/epos2.h diff --git a/epos2/identify.c b/lib/epos2/identify.c similarity index 100% rename from epos2/identify.c rename to lib/epos2/identify.c diff --git a/epos2/identify.h b/lib/epos2/identify.h similarity index 100% rename from epos2/identify.h rename to lib/epos2/identify.h diff --git a/epos2/meson.build b/lib/epos2/meson.build similarity index 100% rename from epos2/meson.build rename to lib/epos2/meson.build diff --git a/ipc/LICENSE b/lib/ipc/LICENSE similarity index 100% rename from ipc/LICENSE rename to lib/ipc/LICENSE diff --git a/ipc/constants.c b/lib/ipc/constants.c similarity index 100% rename from ipc/constants.c rename to lib/ipc/constants.c diff --git a/ipc/constants.h b/lib/ipc/constants.h similarity index 100% rename from ipc/constants.h rename to lib/ipc/constants.h diff --git a/ipc/ipc.c b/lib/ipc/ipc.c similarity index 100% rename from ipc/ipc.c rename to lib/ipc/ipc.c diff --git a/ipc/ipc.h b/lib/ipc/ipc.h similarity index 100% rename from ipc/ipc.h rename to lib/ipc/ipc.h diff --git a/ipc/meson.build b/lib/ipc/meson.build similarity index 100% rename from ipc/meson.build rename to lib/ipc/meson.build diff --git a/ipc/message.c b/lib/ipc/message.c similarity index 100% rename from ipc/message.c rename to lib/ipc/message.c diff --git a/ipc/message.h b/lib/ipc/message.h similarity index 100% rename from ipc/message.h rename to lib/ipc/message.h diff --git a/ipc/os.c b/lib/ipc/os.c similarity index 100% rename from ipc/os.c rename to lib/ipc/os.c diff --git a/ipc/os.h b/lib/ipc/os.h similarity index 100% rename from ipc/os.h rename to lib/ipc/os.h diff --git a/libtestrig_api.h b/lib/libtestrig_api.h similarity index 100% rename from libtestrig_api.h rename to lib/libtestrig_api.h diff --git a/lib/meson.build b/lib/meson.build new file mode 100644 index 0000000..e39e29a --- /dev/null +++ b/lib/meson.build @@ -0,0 +1,9 @@ +## Main Binary Definitions +subdir('ipc') +subdir('epos2') + +srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c', 'ipc/os.c' ] + epos2_srcs +lib = shared_library('testrig', srcs, + dependencies: [ ipc_os_deps, epos2 ], c_args: ['-DCOMPILING_TESTRIG_DLL'] ) +dep = declare_dependency(include_directories: '.', + link_with: lib, dependencies: epos2) diff --git a/meson.build b/meson.build index e86224e..1fc3de5 100644 --- a/meson.build +++ b/meson.build @@ -9,14 +9,5 @@ cpu_architecture = host_machine.cpu_family() valid_os = ['windows', 'linux'] valid_arch = ['x86', 'x86_64', 'aarch64', 'arm'] -## Main Binary Definitions -subdir('ipc') -subdir('epos2') - -srcs = [ 'ipc/ipc.c', 'ipc/message.c', 'ipc/constants.c', 'ipc/os.c' ] + epos2_srcs -lib = shared_library('testrig', srcs, - dependencies: [ ipc_os_deps, epos2 ], c_args: ['-DCOMPILING_TESTRIG_DLL'] ) -dep = declare_dependency(include_directories: '.', - link_with: lib, dependencies: epos2) - +subdir('lib') subdir('test') From ef65536a188de8b053383974c6b63fe47d362b5d Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 00:55:33 -0500 Subject: [PATCH 23/37] Pass struct arrs and not dbl stars --- lib/epos2/identify.c | 42 +++++++++++++++++++++--------------------- lib/epos2/identify.h | 10 +++++----- 2 files changed, 26 insertions(+), 26 deletions(-) diff --git a/lib/epos2/identify.c b/lib/epos2/identify.c index 2ef970e..f549246 100644 --- a/lib/epos2/identify.c +++ b/lib/epos2/identify.c @@ -5,20 +5,20 @@ #include "definitions.h" #include "identify.h" -uint32_t AcquireDeviceNames(struct Controller** controllers_out, int size) { +uint32_t AcquireDeviceNames(struct Controller controllers_out[], int size) { uint32_t error_code = 0; int n = 0; int selection_end; int name_found = VCS_GetDeviceNameSelection( - 1, controllers_out[0]->Name, 8, + 1, controllers_out[0].Name, 8, &selection_end, &error_code); if (name_found != 0) { return error_code; } n++; while (selection_end == 0 && n < size) { name_found = VCS_GetDeviceNameSelection( - 0, controllers_out[n]->Name, 8, + 0, controllers_out[n].Name, 8, &selection_end, &error_code); if (name_found != 0) { return error_code; } @@ -28,22 +28,22 @@ uint32_t AcquireDeviceNames(struct Controller** controllers_out, int size) { return error_code; } -uint32_t AcquireDeviceProtocols(struct Controller** controllers_out, int size) { +uint32_t AcquireDeviceProtocols(struct Controller controllers_out[], int size) { uint32_t error_code = 0; int n = 0; int selection_end; int protocol_found = VCS_GetProtocolStackNameSelection( - controllers_out[0]->Name, 1, - controllers_out[0]->Protocol, 16, + controllers_out[0].Name, 1, + controllers_out[0].Protocol, 16, &selection_end, &error_code); if (protocol_found == 0) { return error_code; } n++; while (selection_end == 0 && n < size) { protocol_found = VCS_GetProtocolStackNameSelection( - controllers_out[n]->Name, 0, - controllers_out[n]->Protocol, 16, + controllers_out[n].Name, 0, + controllers_out[n].Protocol, 16, &selection_end, &error_code); if (protocol_found == 0) { return error_code; } @@ -53,21 +53,21 @@ uint32_t AcquireDeviceProtocols(struct Controller** controllers_out, int size) { return error_code; } -uint32_t AcquireDeviceInterfaces(struct Controller** controllers_out, int size) { +uint32_t AcquireDeviceInterfaces(struct Controller controllers_out[], int size) { uint32_t error_code = 0; int n = 0; int selection_end; int interface_found = VCS_GetInterfaceNameSelection( - controllers_out[0]->Name, controllers_out[0]->Protocol, 1, - controllers_out[0]->Interface, 64, &selection_end, &error_code); + controllers_out[0].Name, controllers_out[0].Protocol, 1, + controllers_out[0].Interface, 64, &selection_end, &error_code); if (interface_found == 0) { return error_code; } n++; while (selection_end == 0 && n < size) { interface_found = VCS_GetInterfaceNameSelection( - controllers_out[n]->Name, controllers_out[n]->Protocol, 0, - controllers_out[n]->Interface, 64, &selection_end, &error_code); + controllers_out[n].Name, controllers_out[n].Protocol, 0, + controllers_out[n].Interface, 64, &selection_end, &error_code); if (interface_found == 0) { return error_code; } n++; @@ -76,21 +76,21 @@ uint32_t AcquireDeviceInterfaces(struct Controller** controllers_out, int size) return error_code; } -uint32_t AcquireDevicePorts(struct Controller** controllers_out, int size) { +uint32_t AcquireDevicePorts(struct Controller controllers_out[], int size) { uint32_t error_code = 0; int n = 0; int selection_end; int port_found = VCS_GetPortNameSelection( - controllers_out[0]->Name, controllers_out[0]->Protocol, controllers_out[0]->Interface, 1, - controllers_out[0]->Port, 8, &selection_end, &error_code); + controllers_out[0].Name, controllers_out[0].Protocol, controllers_out[0].Interface, 1, + controllers_out[0].Port, 8, &selection_end, &error_code); if (port_found == 0) { return error_code; } n++; while (selection_end == 0 && n < size) { port_found = VCS_GetPortNameSelection( - controllers_out[n]->Name, controllers_out[n]->Protocol, controllers_out[n]->Interface, 0, - controllers_out[n]->Port, 8, &selection_end, &error_code); + controllers_out[n].Name, controllers_out[n].Protocol, controllers_out[n].Interface, 0, + controllers_out[n].Port, 8, &selection_end, &error_code); if (port_found == 0) { return error_code; } n++; } @@ -98,15 +98,15 @@ uint32_t AcquireDevicePorts(struct Controller** controllers_out, int size) { return error_code; } -uint32_t AcquireDeviceInfos(struct Controller** controllers_out, int size, int flags) { +uint32_t AcquireDeviceInfos(struct Controller controllers_out[], int size, int flags) { uint32_t error_code = 0; if (flags & (1 << 2)) { memset(controllers_out, 0, sizeof(*controllers_out)); } if (flags & (1 << 1)) { for (int i = 0; i < size; i++) { - strncpy(controllers_out[i]->Name, "EPOS2", 6); - strncpy(controllers_out[i]->Protocol, "CANopen", 8); + strncpy(controllers_out[i].Name, "EPOS2", 6); + strncpy(controllers_out[i].Protocol, "CANopen", 8); } } else { diff --git a/lib/epos2/identify.h b/lib/epos2/identify.h index 2a6bf3c..d711f44 100644 --- a/lib/epos2/identify.h +++ b/lib/epos2/identify.h @@ -25,7 +25,7 @@ enum ACQUIRE_DEVICE_INFORMATION_FLAGS { * * Refer to Page 3-25 of the manual. */ -uint32_t TESTRIG_API AcquireDeviceNames(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDeviceNames(struct Controller controllers_out[], int size); /* * @brief Finds the protocol stacks of the Controller in the array. @@ -33,7 +33,7 @@ uint32_t TESTRIG_API AcquireDeviceNames(struct Controller** controllers_out, int * * Refer to Page 3-26 of the manual. */ -uint32_t TESTRIG_API AcquireDeviceProtocols(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDeviceProtocols(struct Controller controllers_out[], int size); /* * @brief Finds the interfaces of the Controller in the array. @@ -41,7 +41,7 @@ uint32_t TESTRIG_API AcquireDeviceProtocols(struct Controller** controllers_out, * * Refer to Page 3-27 of the manual. */ -uint32_t TESTRIG_API AcquireDeviceInterfaces(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDeviceInterfaces(struct Controller controllers_out[], int size); /* * @brief Finds the ports of the Controller in the array. @@ -49,12 +49,12 @@ uint32_t TESTRIG_API AcquireDeviceInterfaces(struct Controller** controllers_out * * Refer to Page 3-28 of the manual. */ -uint32_t TESTRIG_API AcquireDevicePorts(struct Controller** controllers_out, int size); +uint32_t TESTRIG_API AcquireDevicePorts(struct Controller controllers_out[], int size); /* * @brief Acquire the information on the set number of controllers. */ -uint32_t TESTRIG_API AcquireDeviceInfos(struct Controller** controllers_out, int size, int flags); +uint32_t TESTRIG_API AcquireDeviceInfos(struct Controller controllers_out[], int size, int flags); /* * @brief Set the controller to be identified by the given node on the network. From fd72de5bb15df00f504316a276a1c039427bb4a3 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 16:34:33 -0500 Subject: [PATCH 24/37] Warn about probing for way too many controllers --- lib/epos2/identify.c | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/lib/epos2/identify.c b/lib/epos2/identify.c index f549246..3b08b0a 100644 --- a/lib/epos2/identify.c +++ b/lib/epos2/identify.c @@ -5,6 +5,13 @@ #include "definitions.h" #include "identify.h" +static void warnOverExpectant(const int size, const int n, const char* name) { + if (size <= n) { return; } + printf("Warning: You attempted to probe for more controllers than was connected: "); + printf("%i requested was greater than %i connected: ", size, n); + printf("routine %s\n", name); +} + uint32_t AcquireDeviceNames(struct Controller controllers_out[], int size) { uint32_t error_code = 0; int n = 0; @@ -25,6 +32,7 @@ uint32_t AcquireDeviceNames(struct Controller controllers_out[], int size) { n++; } + warnOverExpectant(size, n, "naming"); return error_code; } @@ -50,6 +58,7 @@ uint32_t AcquireDeviceProtocols(struct Controller controllers_out[], int size) { n++; } + warnOverExpectant(size, n, "protocol finding"); return error_code; } @@ -73,6 +82,7 @@ uint32_t AcquireDeviceInterfaces(struct Controller controllers_out[], int size) n++; } + warnOverExpectant(size, n, "interface finding"); return error_code; } @@ -95,6 +105,7 @@ uint32_t AcquireDevicePorts(struct Controller controllers_out[], int size) { n++; } + warnOverExpectant(size, n, "port finding"); return error_code; } @@ -143,8 +154,8 @@ uint32_t SetDeviceNode(struct Controller* controller_out, void* handle, uint8_t } void PrintControllerCharacteristics(struct Controller* controller) { - printf("- Name: %s\n", controller->Name); - printf("- Node: %i\n", controller->NodeId); - printf("- Protocol: %s\n", controller->Protocol); - printf("- Interface: %s\n", controller->Interface); + printf("- Name: %s\n", controller->Name); + printf("- Node: %i\n", controller->NodeId); + printf("- Protocol: %s\n", controller->Protocol); + printf("- Interface: %s\n", controller->Interface); } From b9010bbf89e8a125ccd3d714398a1c779da34997 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 17:23:47 -0500 Subject: [PATCH 25/37] Change dbl star to arr in connect.c --- lib/epos2/connect.c | 70 ++++++++++++++++++++++++--------------------- lib/epos2/connect.h | 6 +++- 2 files changed, 43 insertions(+), 33 deletions(-) diff --git a/lib/epos2/connect.c b/lib/epos2/connect.c index 888c44a..a974beb 100644 --- a/lib/epos2/connect.c +++ b/lib/epos2/connect.c @@ -4,69 +4,75 @@ #include "definitions.h" #include "identify.h" -uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle) { - uint32_t error_code = 0; - int ret; - - ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); - if (ret == 0) { return error_code; } - - ret = VCS_SetEnableState(device_handle, controller->NodeId, &error_code); - controller->State = CTRL_STATE_OPENED; - return error_code; +static void FailedOpenDevice(uint32_t error_code) { + printf("ERROR 0x%X: Failed to open device with with following characteristics:\n", error_code); } -uint32_t InitializeDevices(struct Controller** controllers_out, void* node_1, void* node_2, void* node_3) { +uint32_t InitializeDevices(struct Controller controllers_out[], void* node_1, void* node_2, void* node_3) { uint32_t error_code = 0; - node_1 = VCS_OpenDevice(controllers_out[0]->Name, - controllers_out[0]->Protocol, - controllers_out[0]->Interface, - controllers_out[0]->Port, + node_1 = VCS_OpenDevice(controllers_out[0].Name, + controllers_out[0].Protocol, + controllers_out[0].Interface, + controllers_out[0].Port, &error_code); - controllers_out[0]->NodeId = 1; + controllers_out[0].NodeId = 1; if (node_1 == 0 || error_code != 0) { - printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); - PrintControllerCharacteristics(controllers_out[0]); - return error_code; + FailedOpenDevice(error_code); + PrintControllerCharacteristics(&controllers_out[0]); + //return error_code; }; - CleanEnableDevice(controllers_out[0], node_1); + CleanEnableDevice(&controllers_out[0], node_1); node_2 = VCS_OpenSubDevice(node_1, - controllers_out[1]->Name, - controllers_out[1]->Protocol, + controllers_out[1].Name, + controllers_out[1].Protocol, &error_code); - controllers_out[1]->NodeId = 2; + controllers_out[1].NodeId = 2; if (node_2 == 0 || error_code != 0) { - printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); - PrintControllerCharacteristics(controllers_out[1]); + FailedOpenDevice(error_code); + PrintControllerCharacteristics(&controllers_out[1]); return error_code; }; - CleanEnableDevice(controllers_out[1], node_2); + CleanEnableDevice(&controllers_out[1], node_2); node_3 = VCS_OpenSubDevice(node_2, - controllers_out[2]->Name, - controllers_out[2]->Protocol, + controllers_out[2].Name, + controllers_out[2].Protocol, &error_code); if (node_3 == 0 || error_code != 0) { - printf("ERROR %uix: Failed to open device with with following characteristics:\n", error_code); - PrintControllerCharacteristics(controllers_out[2]); + FailedOpenDevice(error_code); + PrintControllerCharacteristics(&controllers_out[2]); return error_code; }; - controllers_out[2]->NodeId = 3; + controllers_out[2].NodeId = 3; + + CleanEnableDevice(&controllers_out[2], node_2); - CleanEnableDevice(controllers_out[2], node_2); return 0; } // uint Open +uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle) { + uint32_t error_code = 0; + int ret; + + ret = VCS_ClearFault(device_handle, controller->NodeId, &error_code); + if (ret == 0) { return error_code; } + + ret = VCS_SetEnableState(device_handle, controller->NodeId, &error_code); + controller->State = CTRL_STATE_OPENED; + return error_code; +} + + uint32_t CloseDevice(struct Controller* controller, void* device_handle) { uint32_t error_code = 0; int ret; diff --git a/lib/epos2/connect.h b/lib/epos2/connect.h index c0ce3f2..48121c9 100644 --- a/lib/epos2/connect.h +++ b/lib/epos2/connect.h @@ -23,7 +23,11 @@ uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle); * Refer to Page 162 of the manual under INITIALIZATION, * which describes several of the methods wrapped here. */ -uint32_t TESTRIG_API InitializeDevices(struct Controller** controllers_out, void* node_1, void* node_2, void* node_3); +uint32_t TESTRIG_API InitializeDevices(struct Controller controllers_out[], void* node_1, void* node_2, void* node_3); + +/* + * + */ /* * Closes all connections to the controller From 6b457e84d02c7e7fe7f212ac5967ffb36de4858d Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 18:05:04 -0500 Subject: [PATCH 26/37] Error Decoder --- lib/epos2/connect.c | 14 +++++++++++--- lib/epos2/connect.h | 11 ++++++++++- lib/epos2/epos2.c | 16 ++++++++++++++++ lib/epos2/epos2.h | 11 +++++++++++ lib/epos2/identify.c | 11 ++++++----- 5 files changed, 54 insertions(+), 9 deletions(-) diff --git a/lib/epos2/connect.c b/lib/epos2/connect.c index a974beb..b5216ed 100644 --- a/lib/epos2/connect.c +++ b/lib/epos2/connect.c @@ -1,11 +1,19 @@ #include +#include "epos2.h" #include "connect.h" #include "definitions.h" #include "identify.h" static void FailedOpenDevice(uint32_t error_code) { - printf("ERROR 0x%X: Failed to open device with with following characteristics:\n", error_code); + PrintError(error_code); + printf("Failed to open device with with following characteristics:\n"); +} + +uint32_t InitializeDevice(struct Controller controller_out, void* node) { + uint32_t error_code = 0; + + return error_code; } uint32_t InitializeDevices(struct Controller controllers_out[], void* node_1, void* node_2, void* node_3) { @@ -22,7 +30,7 @@ uint32_t InitializeDevices(struct Controller controllers_out[], void* node_1, vo if (node_1 == 0 || error_code != 0) { FailedOpenDevice(error_code); PrintControllerCharacteristics(&controllers_out[0]); - //return error_code; + return error_code; }; CleanEnableDevice(&controllers_out[0], node_1); @@ -58,7 +66,7 @@ uint32_t InitializeDevices(struct Controller controllers_out[], void* node_1, vo CleanEnableDevice(&controllers_out[2], node_2); return 0; -} // uint Open +} // uint32_t InitializeThreeDevices uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle) { uint32_t error_code = 0; diff --git a/lib/epos2/connect.h b/lib/epos2/connect.h index 48121c9..5f6fe4d 100644 --- a/lib/epos2/connect.h +++ b/lib/epos2/connect.h @@ -15,7 +15,7 @@ namespace VSCL::Rig { extern "C" { #endif // __cplusplus -uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle); +uint32_t TESTRIG_API CleanEnableDevice(struct Controller* controller, void* device_handle); /* * @brief Opens communication to the device and sets its state for a clean init. @@ -23,6 +23,15 @@ uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle); * Refer to Page 162 of the manual under INITIALIZATION, * which describes several of the methods wrapped here. */ +uint32_t TESTRIG_API InitializeDevice(struct Controller controller_out, void* node); + +/* + * @brief Opens communication to the device and sets its state for a clean init. + * This makes a lot of assumptions + * + * Refer to Page 162 of the manual under INITIALIZATION, + * which describes several of the methods wrapped here. + */ uint32_t TESTRIG_API InitializeDevices(struct Controller controllers_out[], void* node_1, void* node_2, void* node_3); /* diff --git a/lib/epos2/epos2.c b/lib/epos2/epos2.c index 489787d..52d9b3d 100644 --- a/lib/epos2/epos2.c +++ b/lib/epos2/epos2.c @@ -1,3 +1,19 @@ +#include #include "epos2.h" const char* DEFAULT_NAME = "EPOS2"; + +int DecodeError(const uint32_t error_code, char* error_msg, uint8_t max_size) { + int ret = VCS_GetErrorInfo(error_code, error_msg, max_size); + if (ret == 0) { printf("ERROR: Failed to decode error\n"); } + + return ret; +} + +int PrintError(const uint32_t error_code) { + char msg[64] = { 0 }; + int ret = DecodeError(error_code, msg, 64); + printf("ERROR 0x%X: %s\n", error_code, msg); + + return ret; +} diff --git a/lib/epos2/epos2.h b/lib/epos2/epos2.h index 3d71909..3eb11a6 100644 --- a/lib/epos2/epos2.h +++ b/lib/epos2/epos2.h @@ -1,6 +1,7 @@ #pragma once #include "libtestrig_api.h" +#include "definitions.h" #include "controller.h" #include "identify.h" #include "connect.h" @@ -12,6 +13,16 @@ extern "C" { extern const char* DEFAULT_NAME; +/* + * @brief Decode a given error code to its corresponding message. + */ +int TESTRIG_API DecodeError(const uint32_t error_code, char* error_msg, uint8_t max_size); + +/* + * @brief Decode and print an error code's corresponding message. + */ +int TESTRIG_API PrintError(const uint32_t error_code); + #ifdef __cplusplus } // extern "C" } // namespace VSCL::Rig diff --git a/lib/epos2/identify.c b/lib/epos2/identify.c index 3b08b0a..a9749cb 100644 --- a/lib/epos2/identify.c +++ b/lib/epos2/identify.c @@ -5,7 +5,7 @@ #include "definitions.h" #include "identify.h" -static void warnOverExpectant(const int size, const int n, const char* name) { +static void WarnOverExpectant(const int size, const int n, const char* name) { if (size <= n) { return; } printf("Warning: You attempted to probe for more controllers than was connected: "); printf("%i requested was greater than %i connected: ", size, n); @@ -32,7 +32,7 @@ uint32_t AcquireDeviceNames(struct Controller controllers_out[], int size) { n++; } - warnOverExpectant(size, n, "naming"); + WarnOverExpectant(size, n, "naming"); return error_code; } @@ -58,7 +58,7 @@ uint32_t AcquireDeviceProtocols(struct Controller controllers_out[], int size) { n++; } - warnOverExpectant(size, n, "protocol finding"); + WarnOverExpectant(size, n, "protocol finding"); return error_code; } @@ -82,7 +82,7 @@ uint32_t AcquireDeviceInterfaces(struct Controller controllers_out[], int size) n++; } - warnOverExpectant(size, n, "interface finding"); + WarnOverExpectant(size, n, "interface finding"); return error_code; } @@ -105,7 +105,7 @@ uint32_t AcquireDevicePorts(struct Controller controllers_out[], int size) { n++; } - warnOverExpectant(size, n, "port finding"); + WarnOverExpectant(size, n, "port finding"); return error_code; } @@ -158,4 +158,5 @@ void PrintControllerCharacteristics(struct Controller* controller) { printf("- Node: %i\n", controller->NodeId); printf("- Protocol: %s\n", controller->Protocol); printf("- Interface: %s\n", controller->Interface); + printf("- Port: %s\n", controller->Port); } From 47e03b05e181eb53ccb27a3d1baf375b2f8eb51f Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 18:13:22 -0500 Subject: [PATCH 27/37] Init/open one device --- lib/epos2/connect.c | 17 ++++++++++++++++- lib/epos2/connect.h | 12 +++++++----- 2 files changed, 23 insertions(+), 6 deletions(-) diff --git a/lib/epos2/connect.c b/lib/epos2/connect.c index b5216ed..9c51f71 100644 --- a/lib/epos2/connect.c +++ b/lib/epos2/connect.c @@ -10,9 +10,24 @@ static void FailedOpenDevice(uint32_t error_code) { printf("Failed to open device with with following characteristics:\n"); } -uint32_t InitializeDevice(struct Controller controller_out, void* node) { +uint32_t InitializeDevice(struct Controller* controller_out, void* node, uint8_t node_id) { uint32_t error_code = 0; + node = VCS_OpenDevice(controller_out->Name, + controller_out->Protocol, + controller_out->Interface, + controller_out->Port, + &error_code); + + controller_out->NodeId = node_id; + + if (node == 0 || error_code != 0) { + FailedOpenDevice(error_code); + PrintControllerCharacteristics(controller_out); + } + + CleanEnableDevice(controller_out, node); + return error_code; } diff --git a/lib/epos2/connect.h b/lib/epos2/connect.h index 5f6fe4d..d7cb75a 100644 --- a/lib/epos2/connect.h +++ b/lib/epos2/connect.h @@ -23,7 +23,7 @@ uint32_t TESTRIG_API CleanEnableDevice(struct Controller* controller, void* devi * Refer to Page 162 of the manual under INITIALIZATION, * which describes several of the methods wrapped here. */ -uint32_t TESTRIG_API InitializeDevice(struct Controller controller_out, void* node); +uint32_t TESTRIG_API InitializeDevice(struct Controller* controller_out, void* node, uint8_t node_id); /* * @brief Opens communication to the device and sets its state for a clean init. @@ -34,10 +34,6 @@ uint32_t TESTRIG_API InitializeDevice(struct Controller controller_out, void* no */ uint32_t TESTRIG_API InitializeDevices(struct Controller controllers_out[], void* node_1, void* node_2, void* node_3); -/* - * - */ - /* * Closes all connections to the controller * @@ -46,6 +42,12 @@ uint32_t TESTRIG_API InitializeDevices(struct Controller controllers_out[], void */ uint32_t TESTRIG_API CloseDevice(struct Controller* controller, void* device_handle); +/* + * + * + */ +uint32_t TESTRIG_API IdentifyFW(void); + #ifdef __cplusplus } // extern "C" } // namespace VSCL::Rig From aab18a797b03ecbd0d3980ed6f11404b7886c7f6 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 18:37:33 -0500 Subject: [PATCH 28/37] Init a CMakeLists.txt --- CMakeLists.txt | 37 +++++++++++++++++++++++++++++++++++++ cmake/FindEPOSCmd.cmake | 0 2 files changed, 37 insertions(+) create mode 100644 CMakeLists.txt create mode 100644 cmake/FindEPOSCmd.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..a787618 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,37 @@ +cmake_minimum_required(VERSION 3.30..4.0) +project(libtestrig + LANGUAGES C) + +list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake") + +set(LIB_DIR "${CMAKE_SOURCE_DIR}/lib") +set(IPC_DIR "${LIB_DIR}/ipc") +set(EPOS_DIR "${LIB_DIR}/epos2") + +set(IPC_SOURCES + "${IPC_DIR}/ipc.c" + "${IPC_DIR}/constants.c" + "${IPC_DIR}/message.c" + "${IPC_DIR}/os.c") + +set(EPOS_SOURCES + "${EPOS_DIR}/epos2.c" + "${EPOS_DIR}/connect.c" + "${EPOS_DIR}/definitions.c" + "${EPOS_DIR}/identify.c") + +set(LIBTESTRIG_SOURCES ${IPC_SOURCES}) + +find_package(EPOSCmd) +if (EPOSCmd_FOUND) + list(APPEND LIBTESTRIG_SOURCES ${EPOS_SOURCES}) +else() + message("Controller capabilities not being built.") +endif() + +add_library(Libtestrig SHARED ${LIBTESTRIG_SOURCES}) +target_include_directories(Libtestrig PUBLIC ${LIB_DIR}) + +if (EPOSCmd_FOUND) + target_link_libraries(Libtestrig PUBLIC EPOSCmd) +endif() diff --git a/cmake/FindEPOSCmd.cmake b/cmake/FindEPOSCmd.cmake new file mode 100644 index 0000000..e69de29 From 88c247b523fe79f3e443c7c3f447ef9a171668cf Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 18:40:29 -0500 Subject: [PATCH 29/37] Build systems actions --- .github/workflows/build-cmake.yml | 55 +++++++++++++++++++ .../workflows/{build.yml => build-meson.yml} | 2 +- 2 files changed, 56 insertions(+), 1 deletion(-) create mode 100644 .github/workflows/build-cmake.yml rename .github/workflows/{build.yml => build-meson.yml} (98%) diff --git a/.github/workflows/build-cmake.yml b/.github/workflows/build-cmake.yml new file mode 100644 index 0000000..197dfe3 --- /dev/null +++ b/.github/workflows/build-cmake.yml @@ -0,0 +1,55 @@ +name: Build and Test with CMake + +on: + pull_request: + branches: ["main"] + paths: + - ".github/workflows/build.yml" + - "ipc/**/*.c" + - "ipc/**/*.h" + - "**/meson.build" + push: + branches: ["main"] + paths: + - ".github/workflows/build.yml" + - "ipc/**/*.c" + - "ipc/**/*.h" + - "**/meson.build" + +jobs: + linux-build-meson: + name: Linux + runs-on: ubuntu-latest + strategy: + fail-fast: true + matrix: + compiler: ["gcc", "clang"] + steps: + - uses: actions/checkout@v5 + - name: Setup CMake + run: | + CC=${{ matrix.compiler }} cmake -S . -B build + - name: Build + run: | + CC=${{ matrix.compiler }} cmake --build build + + windows-build-meson: + name: Windows + runs-on: windows-latest + strategy: + fail-fast: true + matrix: + compiler: ["cl.exe", "gcc.exe"] + steps: + - uses: actions/checkout@v5 + - uses: ilammy/msvc-dev-cmd@v1.13.0 + - name: Setup CMake + run: | + cmake -S . -B build + env: + CC: ${{ matrix.compiler }} + - name: Build + run: | + cmake --build build + env: + CC: ${{ matrix.compiler }} diff --git a/.github/workflows/build.yml b/.github/workflows/build-meson.yml similarity index 98% rename from .github/workflows/build.yml rename to .github/workflows/build-meson.yml index 63addd2..1027a19 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build-meson.yml @@ -1,4 +1,4 @@ -name: Build and Test +name: Build and Test with Meson on: pull_request: From 4407907846aa415cd8ca18ab00cb785d00724153 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 18:45:34 -0500 Subject: [PATCH 30/37] CI Action to target proper files --- .github/workflows/build-cmake.yml | 14 ++++++++------ .github/workflows/build-meson.yml | 4 ++-- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/.github/workflows/build-cmake.yml b/.github/workflows/build-cmake.yml index 197dfe3..5ef83cd 100644 --- a/.github/workflows/build-cmake.yml +++ b/.github/workflows/build-cmake.yml @@ -4,20 +4,22 @@ on: pull_request: branches: ["main"] paths: - - ".github/workflows/build.yml" + - ".github/workflows/build-cmake.yml" - "ipc/**/*.c" - "ipc/**/*.h" - - "**/meson.build" + - "**/CMakeLists.txt" + - "cmake/*.cmake" push: branches: ["main"] paths: - - ".github/workflows/build.yml" + - ".github/workflows/build-cmake.yml" - "ipc/**/*.c" - "ipc/**/*.h" - - "**/meson.build" + - "**/CMakeLists.txt" + - "cmake/*.cmake" jobs: - linux-build-meson: + linux-build-cmake: name: Linux runs-on: ubuntu-latest strategy: @@ -33,7 +35,7 @@ jobs: run: | CC=${{ matrix.compiler }} cmake --build build - windows-build-meson: + windows-build-cmake: name: Windows runs-on: windows-latest strategy: diff --git a/.github/workflows/build-meson.yml b/.github/workflows/build-meson.yml index 1027a19..effcfc6 100644 --- a/.github/workflows/build-meson.yml +++ b/.github/workflows/build-meson.yml @@ -4,14 +4,14 @@ on: pull_request: branches: ["main"] paths: - - ".github/workflows/build.yml" + - ".github/workflows/build-meson.yml" - "ipc/**/*.c" - "ipc/**/*.h" - "**/meson.build" push: branches: ["main"] paths: - - ".github/workflows/build.yml" + - ".github/workflows/build-meson.yml" - "ipc/**/*.c" - "ipc/**/*.h" - "**/meson.build" From 7c039b2eb3a67a8e4651705691ee9551d4172971 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 18:47:07 -0500 Subject: [PATCH 31/37] Less verbose action names --- .github/workflows/build-cmake.yml | 2 +- .github/workflows/build-meson.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-cmake.yml b/.github/workflows/build-cmake.yml index 5ef83cd..82ac45d 100644 --- a/.github/workflows/build-cmake.yml +++ b/.github/workflows/build-cmake.yml @@ -1,4 +1,4 @@ -name: Build and Test with CMake +name: CMake on: pull_request: diff --git a/.github/workflows/build-meson.yml b/.github/workflows/build-meson.yml index effcfc6..9247b4a 100644 --- a/.github/workflows/build-meson.yml +++ b/.github/workflows/build-meson.yml @@ -1,4 +1,4 @@ -name: Build and Test with Meson +name: Meson on: pull_request: From 9781ce425755f016e7f0ef78505d7941c288a80e Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 18:48:46 -0500 Subject: [PATCH 32/37] DLL compile define in CMake --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index a787618..4464302 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,6 +30,7 @@ else() endif() add_library(Libtestrig SHARED ${LIBTESTRIG_SOURCES}) +target_compile_definitions(Libtestrig PRIVATE COMPILING_TESTRIG_DLL) target_include_directories(Libtestrig PUBLIC ${LIB_DIR}) if (EPOSCmd_FOUND) From de504bab13093dacb97296b7bea692eaf8d6bf18 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 19:03:36 -0500 Subject: [PATCH 33/37] Link to windows lib --- CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4464302..a03d4cd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -33,6 +33,10 @@ add_library(Libtestrig SHARED ${LIBTESTRIG_SOURCES}) target_compile_definitions(Libtestrig PRIVATE COMPILING_TESTRIG_DLL) target_include_directories(Libtestrig PUBLIC ${LIB_DIR}) +if (WIN32) + target_link_libraries(Libtestrig PRIVATE Ws2_32) +endif() + if (EPOSCmd_FOUND) target_link_libraries(Libtestrig PUBLIC EPOSCmd) endif() From cb1fb614e1a615262b831e370ebf77036f80793a Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 19:20:43 -0500 Subject: [PATCH 34/37] Device resetter --- lib/epos2/connect.c | 1 - lib/epos2/connect.h | 6 ------ lib/epos2/epos2.c | 11 +++++++++++ lib/epos2/epos2.h | 5 +++++ 4 files changed, 16 insertions(+), 7 deletions(-) diff --git a/lib/epos2/connect.c b/lib/epos2/connect.c index 9c51f71..4731bf2 100644 --- a/lib/epos2/connect.c +++ b/lib/epos2/connect.c @@ -95,7 +95,6 @@ uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle) { return error_code; } - uint32_t CloseDevice(struct Controller* controller, void* device_handle) { uint32_t error_code = 0; int ret; diff --git a/lib/epos2/connect.h b/lib/epos2/connect.h index d7cb75a..4c3273a 100644 --- a/lib/epos2/connect.h +++ b/lib/epos2/connect.h @@ -42,12 +42,6 @@ uint32_t TESTRIG_API InitializeDevices(struct Controller controllers_out[], void */ uint32_t TESTRIG_API CloseDevice(struct Controller* controller, void* device_handle); -/* - * - * - */ -uint32_t TESTRIG_API IdentifyFW(void); - #ifdef __cplusplus } // extern "C" } // namespace VSCL::Rig diff --git a/lib/epos2/epos2.c b/lib/epos2/epos2.c index 52d9b3d..0fe1d56 100644 --- a/lib/epos2/epos2.c +++ b/lib/epos2/epos2.c @@ -17,3 +17,14 @@ int PrintError(const uint32_t error_code) { return ret; } + +uint32_t ResetDevice(void *device_handle, struct Controller *controller_in) { + uint32_t error_code = 0; + int ret = VCS_ResetDevice(device_handle, controller_in->NodeId, &error_code); + if (ret == 0) { + PrintError(error_code); + printf("Device failed to be reset: %s\n", controller_in->Name); + } + + return error_code; +} diff --git a/lib/epos2/epos2.h b/lib/epos2/epos2.h index 3eb11a6..2c351cb 100644 --- a/lib/epos2/epos2.h +++ b/lib/epos2/epos2.h @@ -23,6 +23,11 @@ int TESTRIG_API DecodeError(const uint32_t error_code, char* error_msg, uint8_t */ int TESTRIG_API PrintError(const uint32_t error_code); +/* + * @brief Reset a device. + */ +uint32_t TESTRIG_API ResetDevice(void* device_handle, struct Controller* controller_in); + #ifdef __cplusplus } // extern "C" } // namespace VSCL::Rig From e7031e311a3b51f2ca00d76a57db79267897195b Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 19:32:16 -0500 Subject: [PATCH 35/37] Test rig abort --- CMakeLists.txt | 1 + lib/epos2/epos2.h | 1 + lib/epos2/manage.c | 20 ++++++++++++++++++++ lib/epos2/manage.h | 23 +++++++++++++++++++++++ lib/epos2/meson.build | 2 +- 5 files changed, 46 insertions(+), 1 deletion(-) create mode 100644 lib/epos2/manage.c create mode 100644 lib/epos2/manage.h diff --git a/CMakeLists.txt b/CMakeLists.txt index a03d4cd..99d8705 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,6 +18,7 @@ set(EPOS_SOURCES "${EPOS_DIR}/epos2.c" "${EPOS_DIR}/connect.c" "${EPOS_DIR}/definitions.c" + "${EPOS_DIR}/manage.c" "${EPOS_DIR}/identify.c") set(LIBTESTRIG_SOURCES ${IPC_SOURCES}) diff --git a/lib/epos2/epos2.h b/lib/epos2/epos2.h index 2c351cb..e4535ba 100644 --- a/lib/epos2/epos2.h +++ b/lib/epos2/epos2.h @@ -5,6 +5,7 @@ #include "controller.h" #include "identify.h" #include "connect.h" +#include "manage.h" #ifdef __cplusplus namespace VSCL::Rig { diff --git a/lib/epos2/manage.c b/lib/epos2/manage.c new file mode 100644 index 0000000..3047cd9 --- /dev/null +++ b/lib/epos2/manage.c @@ -0,0 +1,20 @@ +#include +#include "manage.h" + +uint32_t RigAbort(const struct Controller* controller_in, void* device_handle) { + uint32_t error_code = 0; + + printf("WARNING: Attempting to call abort on %s of node %i!!\n", + controller_in->Name, controller_in->NodeId); + + int ret = VCS_SetQuickStopState(device_handle, controller_in->NodeId, &error_code); + if (ret == 0) { + PrintError(error_code); + printf("DANGER: Failed to abort rig operations!\n"); + } + else { + printf("WARNING: Successfully aborted operations.\n"); + } + + return error_code; +} diff --git a/lib/epos2/manage.h b/lib/epos2/manage.h new file mode 100644 index 0000000..7695611 --- /dev/null +++ b/lib/epos2/manage.h @@ -0,0 +1,23 @@ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include "epos2.h" +#include "controller.h" + +#ifdef __cplusplus +} // extern "C" (headers) +namespace VSCL::Rig { +extern "C" { +#endif // __cplusplus + +uint32_t TESTRIG_API RigAbort(const struct Controller* controller_in, void* device_handle); + +#ifdef __cplusplus +} // extern "C" +} // namespace VSCL::Rig +#endif // __cplusplus diff --git a/lib/epos2/meson.build b/lib/epos2/meson.build index 639a765..0e562f5 100644 --- a/lib/epos2/meson.build +++ b/lib/epos2/meson.build @@ -25,7 +25,7 @@ elif (operating_system == 'linux') ) epos2_srcs = [ './epos2/epos2.c', './epos2/definitions.c', - './epos2/identify.c', './epos2/connect.c' ] + './epos2/identify.c', './epos2/connect.c', './epos2/manage.c' ] # Others else From 16f0c3b89877d76876fce97ceb0f8aedaeaf9200 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 23 Mar 2026 19:52:34 -0500 Subject: [PATCH 36/37] Check for uninit handles --- lib/epos2/connect.c | 2 ++ lib/epos2/epos2.c | 1 + lib/epos2/manage.c | 1 + lib/epos2/manage.h | 3 +++ 4 files changed, 7 insertions(+) diff --git a/lib/epos2/connect.c b/lib/epos2/connect.c index 4731bf2..dab2d1f 100644 --- a/lib/epos2/connect.c +++ b/lib/epos2/connect.c @@ -84,6 +84,7 @@ uint32_t InitializeDevices(struct Controller controllers_out[], void* node_1, vo } // uint32_t InitializeThreeDevices uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle) { + if (device_handle == 0) { return 0x2000000B; } uint32_t error_code = 0; int ret; @@ -96,6 +97,7 @@ uint32_t CleanEnableDevice(struct Controller* controller, void* device_handle) { } uint32_t CloseDevice(struct Controller* controller, void* device_handle) { + if (device_handle == 0) { return 0x2000000B; } uint32_t error_code = 0; int ret; diff --git a/lib/epos2/epos2.c b/lib/epos2/epos2.c index 0fe1d56..0770a61 100644 --- a/lib/epos2/epos2.c +++ b/lib/epos2/epos2.c @@ -19,6 +19,7 @@ int PrintError(const uint32_t error_code) { } uint32_t ResetDevice(void *device_handle, struct Controller *controller_in) { + if (device_handle == 0) { return 0x2000000B; } uint32_t error_code = 0; int ret = VCS_ResetDevice(device_handle, controller_in->NodeId, &error_code); if (ret == 0) { diff --git a/lib/epos2/manage.c b/lib/epos2/manage.c index 3047cd9..8a1f81e 100644 --- a/lib/epos2/manage.c +++ b/lib/epos2/manage.c @@ -3,6 +3,7 @@ uint32_t RigAbort(const struct Controller* controller_in, void* device_handle) { uint32_t error_code = 0; + if (device_handle == 0) { return 0x2000000B; } printf("WARNING: Attempting to call abort on %s of node %i!!\n", controller_in->Name, controller_in->NodeId); diff --git a/lib/epos2/manage.h b/lib/epos2/manage.h index 7695611..3bee245 100644 --- a/lib/epos2/manage.h +++ b/lib/epos2/manage.h @@ -15,6 +15,9 @@ namespace VSCL::Rig { extern "C" { #endif // __cplusplus +/* + * Attempt to abort the test rig. + */ uint32_t TESTRIG_API RigAbort(const struct Controller* controller_in, void* device_handle); #ifdef __cplusplus From 1b08c38a2b4b706256fc2fd79064f3ebbd6b1ae1 Mon Sep 17 00:00:00 2001 From: JC Luna Date: Mon, 30 Mar 2026 09:37:19 -0500 Subject: [PATCH 37/37] CMake operate relative to THIS CMakeLists.txt --- CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 99d8705..69f58be 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,9 +2,9 @@ cmake_minimum_required(VERSION 3.30..4.0) project(libtestrig LANGUAGES C) -list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake") +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") -set(LIB_DIR "${CMAKE_SOURCE_DIR}/lib") +set(LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") set(IPC_DIR "${LIB_DIR}/ipc") set(EPOS_DIR "${LIB_DIR}/epos2")