diff --git a/.travis.yml b/.travis.yml
deleted file mode 100644
index 4a3a410..0000000
--- a/.travis.yml
+++ /dev/null
@@ -1,25 +0,0 @@
-# This config file for Travis CI utilizes ros-industrial/industrial_ci package.
-# For more info for the package, see https://github.com/ros-industrial/industrial_ci/blob/master/README.rst
-sudo: required
-dist: trusty
-services:
- - docker
-language: generic
-compiler:
- - gcc
-notifications:
- email: false
-
-env:
- global:
- - CATKIN_PARALLEL_TEST_JOBS=-p1
- - ROS_PARALLEL_TEST_JOBS=-j1
- matrix:
- - ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
- - ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
- - ROS_DISTRO="melodic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
-install:
- - wget -qO- -O EPOS_Library.zip http://academy.maxonjapan.co.jp/wp-content/uploads/manual/epos/EPOS_Linux_Library_E.zip && unzip EPOS_Library.zip && cd EPOS_Linux_Library && sudo bash ./install.sh
- - git clone https://github.com/ros-industrial/industrial_ci.git .ci_config
-script:
- - source .ci_config/travis.sh
diff --git a/README.md b/README.md
index 6efff63..c2e4cd0 100644
--- a/README.md
+++ b/README.md
@@ -1,25 +1,30 @@
# Maxon EPOS Package
-This is a ROS package for Maxon motor & EPOS driver.
+This is a ROS/ROS2 package for Maxon motor & EPOS driver.
## Support Status
This package is **WIP** now.
v1.0.0 supports multiple EPOS device.
## How to use
+> **WARNING** --- The package maxon_epos_example **has NOT** been migrated to ROS2.
+
+In the package maxon_epos_driver you can find an example of launch file and configuration file for runing one motor.
+
+> **VERY IMPORTANT** - Do not set the name of the node when using a launch file to execute the maxon_bringup node. This will rename all rclcpp::Node variables that it node generates and it will be unable to get the motor connection parameters correctly.
### Install Maxon Linux driver
-Firstly you must install maxon official linux driver.
-For detail, please look at [this official pdf](http://academy.maxonjapan.co.jp/wp-content/uploads/manual/epos/EPOS_Command_Library.pdf)
+Firstly you must install maxon official linux driver. [Download EPOS Linux Library here](https://www.maxongroup.com/medias/sys_master/root/8994700394526/EPOS-Linux-Library-En.zip)
+For detail, please look at [this official pdf](https://www.maxongroup.com/medias/sys_master/8823917281310.pdf)
### How to build
Then you have to download this package into your ROS workspace.
```bash
-$ cd ~/catkin_ws/src
-$ git clone https://github.com/iwata-lab/maxon_epos_ros.git
-$ cd ~/catkin_ws
-$ catkin_make
-$ source ~/catkin_ws/devel/setup.bash
+$ cd ~/yourworkspace_ws/src
+$ git clone https://github.com/cristinaluna/maxon_epos_ros.git
+$ cd ~/yourworkspace_ws
+$ colcon build
+$ source ~/yourworkspace_ws/install/setup.bash
```
### How to use nodes
@@ -27,26 +32,26 @@ $ source ~/catkin_ws/devel/setup.bash
You can run nodes by console.
`maxon_bringup` node reads params from ROS parameter server.
```bash
-$ rosrun maxon_epos_driver maxon_bringup
+$ ros2 run maxon_epos_driver maxon_bringup
```
Otherwise, you can refer `maxon_epos_example` package's launch file.
#### Topics
-- `~//get_state` (msg: [maxon_epos_msgs/MotorState](maxon_epos_msgs/msg/MotorState.msg))
+- `~//get_state` (msg: [maxon_epos_msgs/msg/MotorState](maxon_epos_msgs/msg/MotorState.msg))
This topic keep publishing motor current state.
-- `~//set_state` (msg: [maxon_epos_msgs/MotorState](maxon_epos_msgs/msg/MotorState.msg))
+- `~//set_state` (msg: [maxon_epos_msgs/msg/MotorState](maxon_epos_msgs/msg/MotorState.msg))
When you send the goal to epos, use this topic.
-- `~/get_all_state` (msg: [maxon_epos_msgs/MotorStates](maxon_epos_msgs/msg/MotorStates.msg))
+- `~/get_all_state` (msg: [maxon_epos_msgs/msg/MotorStates](maxon_epos_msgs/msg/MotorStates.msg))
This topic keep publishing all motors current states.
-- `~/set_all_state` (msg: [maxon_epos_msgs/MotorStates](maxon_epos_msgs/msg/MotorStates.msg))
+- `~/set_all_state` (msg: [maxon_epos_msgs/msg/MotorStates](maxon_epos_msgs/msg/MotorStates.msg))
When you send the goals to all epos motors, use this topic.
diff --git a/maxon_epos_driver/CMakeLists.txt b/maxon_epos_driver/CMakeLists.txt
index 4a55490..5510ae5 100644
--- a/maxon_epos_driver/CMakeLists.txt
+++ b/maxon_epos_driver/CMakeLists.txt
@@ -1,127 +1,37 @@
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 3.5)
project(maxon_epos_driver)
-## Compile as C++11, supported in ROS Kinetic and newer
-add_compile_options(-std=c++11)
+# Default to C++14
+if(NOT CMAKE_CXX_STANDARD)
+ set(CMAKE_CXX_STANDARD 14)
+endif()
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS
- roscpp
- std_msgs
- maxon_epos_msgs
-)
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
-
-
-## Uncomment this if the package has a setup.py. This macro ensures
-## modules and global scripts declared therein get installed
-## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
-# catkin_python_setup()
-
-################################################
-## Declare ROS messages, services and actions ##
-################################################
-
-## To declare and build messages, services or actions from within this
-## package, follow these steps:
-## * Let MSG_DEP_SET be the set of packages whose message types you use in
-## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
-## * In the file package.xml:
-## * add a build_depend tag for "message_generation"
-## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
-## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
-## but can be declared for certainty nonetheless:
-## * add a exec_depend tag for "message_runtime"
-## * In this file (CMakeLists.txt):
-## * add "message_generation" and every package in MSG_DEP_SET to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * add "message_runtime" and every package in MSG_DEP_SET to
-## catkin_package(CATKIN_DEPENDS ...)
-## * uncomment the add_*_files sections below as needed
-## and list every .msg/.srv/.action file to be processed
-## * uncomment the generate_messages entry below
-## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-
-## Generate services in the 'srv' folder
-# add_service_files(
-# FILES
-# Service1.srv
-# Service2.srv
-# )
-
-## Generate actions in the 'action' folder
-# add_action_files(
-# FILES
-# Action1.action
-# Action2.action
-# )
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# std_msgs
-# )
-
-################################################
-## Declare ROS dynamic reconfigure parameters ##
-################################################
-
-## To declare and build dynamic reconfigure parameters within this
-## package, follow these steps:
-## * In the file package.xml:
-## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
-## * In this file (CMakeLists.txt):
-## * add "dynamic_reconfigure" to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * uncomment the "generate_dynamic_reconfigure_options" section below
-## and list every .cfg file to be processed
-
-## Generate dynamic reconfigure parameters in the 'cfg' folder
-# generate_dynamic_reconfigure_options(
-# cfg/DynReconf1.cfg
-# cfg/DynReconf2.cfg
-# )
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## INCLUDE_DIRS: uncomment this if your package contains header files
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
-catkin_package(
- INCLUDE_DIRS include
- LIBRARIES maxon_epos_driver
- CATKIN_DEPENDS message_runtime roscpp std_msgs
- # DEPENDS system_lib
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+find_package(ament_cmake REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(rclcpp_components REQUIRED)
+find_package(std_msgs REQUIRED)
+find_package(geometry_msgs REQUIRED)
+find_package(maxon_epos_msgs REQUIRED)
+
+set(DEPENDENCIES
+ "geometry_msgs"
+ "rclcpp"
+ "std_msgs"
+ "maxon_epos_msgs"
)
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
include_directories(
include
- ${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
-add_library(${PROJECT_NAME}
+add_library(${PROJECT_NAME} SHARED
src/lib/EposMotor.cpp
src/lib/EposManager.cpp
src/lib/Device.cpp
@@ -131,81 +41,42 @@ add_library(${PROJECT_NAME}
src/lib/control/EposProfileVelocityMode.cpp
src/lib/control/EposCurrentMode.cpp
)
+ament_target_dependencies(maxon_epos_driver
+ rclcpp_components
+ rclcpp
+ geometry_msgs
+ std_msgs
+ maxon_epos_msgs
+)
+target_link_libraries(maxon_epos_driver -lEposCmd)
+ament_export_libraries(maxon_epos_driver)
-## Add cmake target dependencies of the library
-## as an example, code may need to be generated before libraries
-## either from message generation or dynamic reconfigure
-add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
-
-## Declare a C++ executable
-## With catkin_make all packages are built within a single CMake context
-## The recommended prefix ensures that target names across packages don't collide
add_executable(maxon_bringup src/node/maxon_bringup.cpp)
+ament_target_dependencies(maxon_bringup
+ rclcpp_components
+ rclcpp
+ geometry_msgs
+ std_msgs
+ maxon_epos_msgs
+)
+target_link_libraries(maxon_bringup maxon_epos_driver -lEposCmd)
-## Rename C++ executable without prefix
-## The above recommended prefix causes long target names, the following renames the
-## target back to the shorter version for ease of user use
-## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
-# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
-## Add cmake target dependencies of the executable
-## same as for the library above
-add_dependencies(maxon_bringup ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+install(DIRECTORY include/
+ DESTINATION include)
+ament_export_include_directories(include)
-## Specify libraries to link a library or executable target against
-target_link_libraries(${PROJECT_NAME}
- ${catkin_LIBRARIES}
- EposCmd
-)
-target_link_libraries(maxon_bringup
- ${PROJECT_NAME}
- ${catkin_LIBRARIES}
-)
+install(TARGETS ${PROJECT_NAME}
+ DESTINATION lib)
+
+install(TARGETS maxon_bringup
+ DESTINATION lib/${PROJECT_NAME})
+
+install(DIRECTORY launch
+ DESTINATION share/${PROJECT_NAME}/)
+
+install(DIRECTORY config
+ DESTINATION share/${PROJECT_NAME}/)
+
+ament_package()
-#############
-## Install ##
-#############
-
-# all install targets should use catkin DESTINATION variables
-# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
-
-## Mark executable scripts (Python etc.) for installation
-## in contrast to setup.py, you can choose the destination
-# install(PROGRAMS
-# scripts/my_python_script
-# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark executables and/or libraries for installation
-# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
-# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark cpp header files for installation
-# install(DIRECTORY include/${PROJECT_NAME}/
-# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
-# FILES_MATCHING PATTERN "*.h"
-# PATTERN ".svn" EXCLUDE
-# )
-
-## Mark other files for installation (e.g. launch and bag files, etc.)
-# install(FILES
-# # myfile1
-# # myfile2
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-# )
-
-#############
-## Testing ##
-#############
-
-## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_maxon_epos_sample.cpp)
-# if(TARGET ${PROJECT_NAME}-test)
-# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
-# endif()
-
-## Add folders to be run by python nosetests
-# catkin_add_nosetests(test)
diff --git a/maxon_epos_driver/config/test_1motor.yaml b/maxon_epos_driver/config/test_1motor.yaml
new file mode 100644
index 0000000..09ee731
--- /dev/null
+++ b/maxon_epos_driver/config/test_1motor.yaml
@@ -0,0 +1,39 @@
+maxon_bringup:
+ ros__parameters:
+ motor_names: ["motor1"]
+
+motor1:
+ ros__parameters:
+ # epos's node information (must be enough to identify the node)
+ device: 'EPOS4' # default: 'EPOS4'
+ protocol_stack: 'CANopen' # default: 'MAXON SERIAL V2'
+ interface: 'USB' # default: 'USB'
+ port: 'USB0' # default: 'USB0'
+ node_id: 1 # default: 0 (invalid)
+
+ # communication settings (optional)
+ # 'device' is a set of types of device, protocol_stack, interface, and port.
+ # order of node initialization is that of commandline arguments.
+ baudrate: 1000000 # default: 0 (keep current baudrate)
+ timeout: 500 # [ms], default: 0 (keep current timeout)
+
+ # general parameters (optional)
+ use_ros_unit: true # use ros standard units (rad, rad/s, Nm) in hardware interfaces
+ # or epos standard units (quad count of encoder pulse(qc), rpm, mNm)
+ # (default: false)
+
+ # epos's operation mode (required)
+ control_mode: "profile_position"
+
+ # encoder parameters (required)
+ encoder:
+ type: 1 # 1: INC 3CH, 2: INC 2CH, 4: SSI ABS BIN, 5: SSI ABS GRY
+ resolution: 1024 # encoder resolution
+ gear_ratio: 243 # gear ratio of motor
+ inverted_polarity: false
+
+ # profile position mode configs (optional)
+ position_profile:
+ velocity: 10000 # [rpm]
+ acceleration: 8000 # [rpm/s]
+ deceleration: 9000 # [rpm/s]
\ No newline at end of file
diff --git a/maxon_epos_driver/include/maxon_epos_driver/Definitions.h b/maxon_epos_driver/include/maxon_epos_driver/Definitions.h
index 7d92e85..bef8e23 100644
--- a/maxon_epos_driver/include/maxon_epos_driver/Definitions.h
+++ b/maxon_epos_driver/include/maxon_epos_driver/Definitions.h
@@ -20,7 +20,11 @@
int CreateCommunication();
int DeleteCommunication();
-// INITIALISATION FUNCTIONS
+// Data Recorder
+ int CreateDataRecorderCmdManager(void* KeyHandle);
+ int DeleteDataRecorderCmdManager();
+
+ // INITIALISATION FUNCTIONS
#define Initialisation_DllExport extern "C"
#define HelpFunctions_DllExport extern "C"
// CONFIGURATION FUNCTIONS
@@ -40,6 +44,8 @@
#define MasterEncoderMode_DllExport extern "C"
#define StepDirectionMode_DllExport extern "C"
#define InputsOutputs_DllExport extern "C"
+// DATA RECORDING FUNCTIONS
+ #define DataRecording_DllExport extern "C"
// LOW LAYER FUNCTIONS
#define CanLayer_DllExport extern "C"
@@ -95,10 +101,14 @@
//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);
@@ -106,11 +116,13 @@
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);
@@ -179,7 +191,9 @@
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
@@ -252,7 +266,9 @@
//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);
@@ -280,7 +296,7 @@
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);
+ 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);
@@ -300,6 +316,33 @@
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);
+
/*************************************************************************************************************************************
* LOW LAYER FUNCTIONS
*************************************************************************************************************************************/
@@ -523,3 +566,4 @@
const unsigned short EG_DLPC_MAIN_LOOP_FILTER_COEFFICIENT_E = 124;
#endif //_H_LINUX_EPOSCMD_
+
diff --git a/maxon_epos_driver/include/maxon_epos_driver/Device.hpp b/maxon_epos_driver/include/maxon_epos_driver/Device.hpp
index 181db37..cc61bed 100644
--- a/maxon_epos_driver/include/maxon_epos_driver/Device.hpp
+++ b/maxon_epos_driver/include/maxon_epos_driver/Device.hpp
@@ -12,7 +12,7 @@
#include
#include
#include