diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index f679a5e3..006f2cda 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -21,6 +21,12 @@ jobs: ROBOT_MODEL: 'ur5e' URSIM_VERSION: '5.9.4' PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series' + - DOCKER_RUN_OPTS: --network ursim_net + BEFORE_INIT: 'apt-get update -qq && apt-get install -y iproute2 iputils-ping && ip addr && ping -c5 192.168.56.101' + CTEST_OUTPUT_ON_FAILURE: 1 + ROBOT_MODEL: 'ur20' + URSIM_VERSION: 'latest' + PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series' steps: - uses: actions/checkout@v1 diff --git a/README.md b/README.md index bc042cf0..1d713201 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,11 @@ A C++ library for accessing Universal Robots interfaces. With this library C++-b implemented in order to create external applications leveraging the versatility of Universal Robots robotic manipulators. + +
+ Universal Robot family +
+ ## Requirements * **Polyscope** (The software running on the robot controller) version **3.14.3** (for CB3-Series), diff --git a/doc/resources/family_photo.png b/doc/resources/family_photo.png new file mode 100644 index 00000000..678d312d Binary files /dev/null and b/doc/resources/family_photo.png differ diff --git a/src/rtde/data_package.cpp b/src/rtde/data_package.cpp index bb3ba679..efa5b669 100644 --- a/src/rtde/data_package.cpp +++ b/src/rtde/data_package.cpp @@ -42,9 +42,8 @@ std::unordered_map DataPackage::g_ { "target_moment", vector6d_t() }, { "actual_q", vector6d_t() }, { "actual_qd", vector6d_t() }, - { "actual_qdd", vector6d_t() }, { "actual_current", vector6d_t() }, - { "actual_moment", vector6d_t() }, + { "actual_current_window", vector6d_t() }, { "joint_control_output", vector6d_t() }, { "actual_TCP_pose", vector6d_t() }, { "actual_TCP_speed", vector6d_t() }, @@ -57,6 +56,7 @@ std::unordered_map DataPackage::g_ { "robot_mode", int32_t() }, { "joint_mode", vector6int32_t() }, { "safety_mode", int32_t() }, + { "safety_status", int32_t() }, { "actual_tool_accelerometer", vector3d_t() }, { "speed_scaling", double() }, { "target_speed_fraction", double() }, @@ -88,7 +88,7 @@ std::unordered_map DataPackage::g_ { "tool_output_voltage", int32_t() }, { "tool_output_current", double() }, { "tool_temperature", double() }, - { "tool_force_scalar", double() }, + { "tcp_force_scalar", double() }, { "output_bit_registers0_to_31", uint32_t() }, { "output_bit_registers32_to_63", uint32_t() }, { "output_bit_register_0", bool() }, @@ -548,7 +548,18 @@ std::unordered_map DataPackage::g_ { "configurable_digital_output_mask", uint8_t() }, { "configurable_digital_output", uint8_t() }, { "tool_digital_output_mask", uint8_t() }, + { "tool_output_mode", uint8_t() }, + { "tool_digital_output0_mode", uint8_t() }, + { "tool_digital_output1_mode", uint8_t() }, { "tool_digital_output", uint8_t() }, + { "payload", double() }, + { "payload_cog", vector3d_t() }, + { "payload_inertia", vector6d_t() }, + { "script_control_line", uint32_t() }, + { "ft_raw_wrench", vector6d_t() }, + { "joint_position_deviation_ratio", double() }, + { "collision_detection_ratio", double() }, + { "time_scale_source", int32_t() }, { "standard_analog_output_mask", uint8_t() }, { "standard_analog_output_type", uint8_t() }, { "standard_analog_output_0", double() }, diff --git a/src/rtde/rtde_client.cpp b/src/rtde/rtde_client.cpp index 404276db..f3158798 100644 --- a/src/rtde/rtde_client.cpp +++ b/src/rtde/rtde_client.cpp @@ -254,7 +254,7 @@ void RTDEClient::setupOutputs(const uint16_t protocol_version) unsigned int num_retries = 0; size_t size; size_t written; - uint8_t buffer[4096]; + uint8_t buffer[8192]; URCL_LOG_INFO("Setting up RTDE communication with frequency %f", target_frequency_); if (protocol_version == 2) { diff --git a/tests/test_rtde_client.cpp b/tests/test_rtde_client.cpp index b52c4411..8158dac9 100644 --- a/tests/test_rtde_client.cpp +++ b/tests/test_rtde_client.cpp @@ -26,16 +26,371 @@ */ //---------------------------------------------------------------------- +#include #include +#include #include +#include +#include +#include #include "ur_client_library/exceptions.h" #include +#include using namespace urcl; std::string ROBOT_IP = "192.168.56.101"; +// Based on https://www.universal-robots.com/articles/ur/interface-communication/real-time-data-exchange-rtde-guide/ +using MinCbSeriesVersion = std::optional; +using MinESeriesVersion = std::optional; +using OutputNamesWithCompatibility = std::unordered_map>; +const OutputNamesWithCompatibility EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY = { + { "timestamp", { std::nullopt, std::nullopt } }, + { "target_q", { std::nullopt, std::nullopt } }, + { "target_qd", { std::nullopt, std::nullopt } }, + { "target_qdd", { std::nullopt, std::nullopt } }, + { "target_current", { std::nullopt, std::nullopt } }, + { "target_moment", { std::nullopt, std::nullopt } }, + { "actual_q", { std::nullopt, std::nullopt } }, + { "actual_qd", { std::nullopt, std::nullopt } }, + { "actual_current", { std::nullopt, std::nullopt } }, + { "actual_current_window", { std::nullopt, std::nullopt } }, + { "joint_control_output", { std::nullopt, std::nullopt } }, + { "actual_TCP_pose", { std::nullopt, std::nullopt } }, + { "actual_TCP_speed", { std::nullopt, std::nullopt } }, + { "actual_TCP_force", { std::nullopt, std::nullopt } }, + { "target_TCP_pose", { std::nullopt, std::nullopt } }, + { "target_TCP_speed", { std::nullopt, std::nullopt } }, + { "actual_digital_input_bits", { std::nullopt, std::nullopt } }, + { "joint_temperatures", { std::nullopt, std::nullopt } }, + { "actual_execution_time", { std::nullopt, std::nullopt } }, + { "robot_mode", { std::nullopt, std::nullopt } }, + { "joint_mode", { std::nullopt, std::nullopt } }, + { "safety_mode", { std::nullopt, std::nullopt } }, + { "safety_status", { "3.10.0", "5.4.0" } }, + { "actual_tool_accelerometer", { std::nullopt, std::nullopt } }, + { "speed_scaling", { std::nullopt, std::nullopt } }, + { "target_speed_fraction", { std::nullopt, std::nullopt } }, + { "actual_momentum", { std::nullopt, std::nullopt } }, + { "actual_main_voltage", { std::nullopt, std::nullopt } }, + { "actual_robot_voltage", { std::nullopt, std::nullopt } }, + { "actual_robot_current", { std::nullopt, std::nullopt } }, + { "actual_joint_voltage", { std::nullopt, std::nullopt } }, + { "actual_digital_output_bits", { std::nullopt, std::nullopt } }, + { "runtime_state", { std::nullopt, std::nullopt } }, + { "elbow_position", { "3.5.0", "5.0.0" } }, + { "elbow_velocity", { "3.5.0", "5.0.0" } }, + { "robot_status_bits", { std::nullopt, std::nullopt } }, + { "safety_status_bits", { std::nullopt, std::nullopt } }, + { "analog_io_types", { std::nullopt, std::nullopt } }, + { "standard_analog_input0", { std::nullopt, std::nullopt } }, + { "standard_analog_input1", { std::nullopt, std::nullopt } }, + { "standard_analog_output0", { std::nullopt, std::nullopt } }, + { "standard_analog_output1", { std::nullopt, std::nullopt } }, + { "io_current", { std::nullopt, std::nullopt } }, + { "euromap67_input_bits", { std::nullopt, std::nullopt } }, + { "euromap67_output_bits", { std::nullopt, std::nullopt } }, + { "euromap67_24V_voltage", { std::nullopt, std::nullopt } }, + { "euromap67_24V_current", { std::nullopt, std::nullopt } }, + { "tool_mode", { std::nullopt, std::nullopt } }, + { "tool_analog_input_types", { std::nullopt, std::nullopt } }, + { "tool_analog_input0", { std::nullopt, std::nullopt } }, + { "tool_analog_input1", { std::nullopt, std::nullopt } }, + { "tool_output_voltage", { std::nullopt, std::nullopt } }, + { "tool_output_current", { std::nullopt, std::nullopt } }, + { "tool_temperature", { std::nullopt, std::nullopt } }, + { "tcp_force_scalar", { std::nullopt, std::nullopt } }, + { "output_bit_registers0_to_31", { std::nullopt, std::nullopt } }, + { "output_bit_registers32_to_63", { std::nullopt, std::nullopt } }, + { "output_bit_register_64", { "3.9.0", "5.3.0" } }, + { "output_bit_register_65", { "3.9.0", "5.3.0" } }, + { "output_bit_register_66", { "3.9.0", "5.3.0" } }, + { "output_bit_register_67", { "3.9.0", "5.3.0" } }, + { "output_bit_register_68", { "3.9.0", "5.3.0" } }, + { "output_bit_register_69", { "3.9.0", "5.3.0" } }, + { "output_bit_register_70", { "3.9.0", "5.3.0" } }, + { "output_bit_register_71", { "3.9.0", "5.3.0" } }, + { "output_bit_register_72", { "3.9.0", "5.3.0" } }, + { "output_bit_register_73", { "3.9.0", "5.3.0" } }, + { "output_bit_register_74", { "3.9.0", "5.3.0" } }, + { "output_bit_register_75", { "3.9.0", "5.3.0" } }, + { "output_bit_register_76", { "3.9.0", "5.3.0" } }, + { "output_bit_register_77", { "3.9.0", "5.3.0" } }, + { "output_bit_register_78", { "3.9.0", "5.3.0" } }, + { "output_bit_register_79", { "3.9.0", "5.3.0" } }, + { "output_bit_register_80", { "3.9.0", "5.3.0" } }, + { "output_bit_register_81", { "3.9.0", "5.3.0" } }, + { "output_bit_register_82", { "3.9.0", "5.3.0" } }, + { "output_bit_register_83", { "3.9.0", "5.3.0" } }, + { "output_bit_register_84", { "3.9.0", "5.3.0" } }, + { "output_bit_register_85", { "3.9.0", "5.3.0" } }, + { "output_bit_register_86", { "3.9.0", "5.3.0" } }, + { "output_bit_register_87", { "3.9.0", "5.3.0" } }, + { "output_bit_register_88", { "3.9.0", "5.3.0" } }, + { "output_bit_register_89", { "3.9.0", "5.3.0" } }, + { "output_bit_register_90", { "3.9.0", "5.3.0" } }, + { "output_bit_register_91", { "3.9.0", "5.3.0" } }, + { "output_bit_register_92", { "3.9.0", "5.3.0" } }, + { "output_bit_register_93", { "3.9.0", "5.3.0" } }, + { "output_bit_register_94", { "3.9.0", "5.3.0" } }, + { "output_bit_register_95", { "3.9.0", "5.3.0" } }, + { "output_bit_register_96", { "3.9.0", "5.3.0" } }, + { "output_bit_register_97", { "3.9.0", "5.3.0" } }, + { "output_bit_register_98", { "3.9.0", "5.3.0" } }, + { "output_bit_register_99", { "3.9.0", "5.3.0" } }, + { "output_bit_register_100", { "3.9.0", "5.3.0" } }, + { "output_bit_register_101", { "3.9.0", "5.3.0" } }, + { "output_bit_register_102", { "3.9.0", "5.3.0" } }, + { "output_bit_register_103", { "3.9.0", "5.3.0" } }, + { "output_bit_register_104", { "3.9.0", "5.3.0" } }, + { "output_bit_register_105", { "3.9.0", "5.3.0" } }, + { "output_bit_register_106", { "3.9.0", "5.3.0" } }, + { "output_bit_register_107", { "3.9.0", "5.3.0" } }, + { "output_bit_register_108", { "3.9.0", "5.3.0" } }, + { "output_bit_register_109", { "3.9.0", "5.3.0" } }, + { "output_bit_register_110", { "3.9.0", "5.3.0" } }, + { "output_bit_register_111", { "3.9.0", "5.3.0" } }, + { "output_bit_register_112", { "3.9.0", "5.3.0" } }, + { "output_bit_register_113", { "3.9.0", "5.3.0" } }, + { "output_bit_register_114", { "3.9.0", "5.3.0" } }, + { "output_bit_register_115", { "3.9.0", "5.3.0" } }, + { "output_bit_register_116", { "3.9.0", "5.3.0" } }, + { "output_bit_register_117", { "3.9.0", "5.3.0" } }, + { "output_bit_register_118", { "3.9.0", "5.3.0" } }, + { "output_bit_register_119", { "3.9.0", "5.3.0" } }, + { "output_bit_register_120", { "3.9.0", "5.3.0" } }, + { "output_bit_register_121", { "3.9.0", "5.3.0" } }, + { "output_bit_register_122", { "3.9.0", "5.3.0" } }, + { "output_bit_register_123", { "3.9.0", "5.3.0" } }, + { "output_bit_register_124", { "3.9.0", "5.3.0" } }, + { "output_bit_register_125", { "3.9.0", "5.3.0" } }, + { "output_bit_register_126", { "3.9.0", "5.3.0" } }, + { "output_bit_register_127", { "3.9.0", "5.3.0" } }, + { "output_int_register_0", { "3.4.0", std::nullopt } }, + { "output_int_register_1", { "3.4.0", std::nullopt } }, + { "output_int_register_2", { "3.4.0", std::nullopt } }, + { "output_int_register_3", { "3.4.0", std::nullopt } }, + { "output_int_register_4", { "3.4.0", std::nullopt } }, + { "output_int_register_5", { "3.4.0", std::nullopt } }, + { "output_int_register_6", { "3.4.0", std::nullopt } }, + { "output_int_register_7", { "3.4.0", std::nullopt } }, + { "output_int_register_8", { "3.4.0", std::nullopt } }, + { "output_int_register_9", { "3.4.0", std::nullopt } }, + { "output_int_register_10", { "3.4.0", std::nullopt } }, + { "output_int_register_11", { "3.4.0", std::nullopt } }, + { "output_int_register_12", { "3.4.0", std::nullopt } }, + { "output_int_register_13", { "3.4.0", std::nullopt } }, + { "output_int_register_14", { "3.4.0", std::nullopt } }, + { "output_int_register_15", { "3.4.0", std::nullopt } }, + { "output_int_register_16", { "3.4.0", std::nullopt } }, + { "output_int_register_17", { "3.4.0", std::nullopt } }, + { "output_int_register_18", { "3.4.0", std::nullopt } }, + { "output_int_register_19", { "3.4.0", std::nullopt } }, + { "output_int_register_20", { "3.4.0", std::nullopt } }, + { "output_int_register_21", { "3.4.0", std::nullopt } }, + { "output_int_register_22", { "3.4.0", std::nullopt } }, + { "output_int_register_23", { "3.4.0", std::nullopt } }, + { "output_int_register_24", { "3.9.0", "5.3.0" } }, + { "output_int_register_25", { "3.9.0", "5.3.0" } }, + { "output_int_register_26", { "3.9.0", "5.3.0" } }, + { "output_int_register_27", { "3.9.0", "5.3.0" } }, + { "output_int_register_28", { "3.9.0", "5.3.0" } }, + { "output_int_register_29", { "3.9.0", "5.3.0" } }, + { "output_int_register_30", { "3.9.0", "5.3.0" } }, + { "output_int_register_31", { "3.9.0", "5.3.0" } }, + { "output_int_register_32", { "3.9.0", "5.3.0" } }, + { "output_int_register_33", { "3.9.0", "5.3.0" } }, + { "output_int_register_34", { "3.9.0", "5.3.0" } }, + { "output_int_register_35", { "3.9.0", "5.3.0" } }, + { "output_int_register_36", { "3.9.0", "5.3.0" } }, + { "output_int_register_37", { "3.9.0", "5.3.0" } }, + { "output_int_register_38", { "3.9.0", "5.3.0" } }, + { "output_int_register_39", { "3.9.0", "5.3.0" } }, + { "output_int_register_40", { "3.9.0", "5.3.0" } }, + { "output_int_register_41", { "3.9.0", "5.3.0" } }, + { "output_int_register_42", { "3.9.0", "5.3.0" } }, + { "output_int_register_43", { "3.9.0", "5.3.0" } }, + { "output_int_register_44", { "3.9.0", "5.3.0" } }, + { "output_int_register_45", { "3.9.0", "5.3.0" } }, + { "output_int_register_46", { "3.9.0", "5.3.0" } }, + { "output_int_register_47", { "3.9.0", "5.3.0" } }, + { "output_double_register_0", { "3.4.0", std::nullopt } }, + { "output_double_register_1", { "3.4.0", std::nullopt } }, + { "output_double_register_2", { "3.4.0", std::nullopt } }, + { "output_double_register_3", { "3.4.0", std::nullopt } }, + { "output_double_register_4", { "3.4.0", std::nullopt } }, + { "output_double_register_5", { "3.4.0", std::nullopt } }, + { "output_double_register_6", { "3.4.0", std::nullopt } }, + { "output_double_register_7", { "3.4.0", std::nullopt } }, + { "output_double_register_8", { "3.4.0", std::nullopt } }, + { "output_double_register_9", { "3.4.0", std::nullopt } }, + { "output_double_register_10", { "3.4.0", std::nullopt } }, + { "output_double_register_11", { "3.4.0", std::nullopt } }, + { "output_double_register_12", { "3.4.0", std::nullopt } }, + { "output_double_register_13", { "3.4.0", std::nullopt } }, + { "output_double_register_14", { "3.4.0", std::nullopt } }, + { "output_double_register_15", { "3.4.0", std::nullopt } }, + { "output_double_register_16", { "3.4.0", std::nullopt } }, + { "output_double_register_17", { "3.4.0", std::nullopt } }, + { "output_double_register_18", { "3.4.0", std::nullopt } }, + { "output_double_register_19", { "3.4.0", std::nullopt } }, + { "output_double_register_20", { "3.4.0", std::nullopt } }, + { "output_double_register_21", { "3.4.0", std::nullopt } }, + { "output_double_register_22", { "3.4.0", std::nullopt } }, + { "output_double_register_23", { "3.4.0", std::nullopt } }, + { "output_double_register_24", { "3.9.0", "5.3.0" } }, + { "output_double_register_25", { "3.9.0", "5.3.0" } }, + { "output_double_register_26", { "3.9.0", "5.3.0" } }, + { "output_double_register_27", { "3.9.0", "5.3.0" } }, + { "output_double_register_28", { "3.9.0", "5.3.0" } }, + { "output_double_register_29", { "3.9.0", "5.3.0" } }, + { "output_double_register_30", { "3.9.0", "5.3.0" } }, + { "output_double_register_31", { "3.9.0", "5.3.0" } }, + { "output_double_register_32", { "3.9.0", "5.3.0" } }, + { "output_double_register_33", { "3.9.0", "5.3.0" } }, + { "output_double_register_34", { "3.9.0", "5.3.0" } }, + { "output_double_register_35", { "3.9.0", "5.3.0" } }, + { "output_double_register_36", { "3.9.0", "5.3.0" } }, + { "output_double_register_37", { "3.9.0", "5.3.0" } }, + { "output_double_register_38", { "3.9.0", "5.3.0" } }, + { "output_double_register_39", { "3.9.0", "5.3.0" } }, + { "output_double_register_40", { "3.9.0", "5.3.0" } }, + { "output_double_register_41", { "3.9.0", "5.3.0" } }, + { "output_double_register_42", { "3.9.0", "5.3.0" } }, + { "output_double_register_43", { "3.9.0", "5.3.0" } }, + { "output_double_register_44", { "3.9.0", "5.3.0" } }, + { "output_double_register_45", { "3.9.0", "5.3.0" } }, + { "output_double_register_46", { "3.9.0", "5.3.0" } }, + { "output_double_register_47", { "3.9.0", "5.3.0" } }, + { "input_bit_registers0_to_31", { "3.4.0", std::nullopt } }, + { "input_bit_registers32_to_63", { "3.4.0", std::nullopt } }, + { "input_bit_register_64", { "3.9.0", "5.3.0" } }, + { "input_bit_register_65", { "3.9.0", "5.3.0" } }, + { "input_bit_register_66", { "3.9.0", "5.3.0" } }, + { "input_bit_register_67", { "3.9.0", "5.3.0" } }, + { "input_bit_register_68", { "3.9.0", "5.3.0" } }, + { "input_bit_register_69", { "3.9.0", "5.3.0" } }, + { "input_bit_register_70", { "3.9.0", "5.3.0" } }, + { "input_bit_register_71", { "3.9.0", "5.3.0" } }, + { "input_bit_register_72", { "3.9.0", "5.3.0" } }, + { "input_bit_register_73", { "3.9.0", "5.3.0" } }, + { "input_bit_register_74", { "3.9.0", "5.3.0" } }, + { "input_bit_register_75", { "3.9.0", "5.3.0" } }, + { "input_bit_register_76", { "3.9.0", "5.3.0" } }, + { "input_bit_register_77", { "3.9.0", "5.3.0" } }, + { "input_bit_register_78", { "3.9.0", "5.3.0" } }, + { "input_bit_register_79", { "3.9.0", "5.3.0" } }, + { "input_bit_register_80", { "3.9.0", "5.3.0" } }, + { "input_bit_register_81", { "3.9.0", "5.3.0" } }, + { "input_bit_register_82", { "3.9.0", "5.3.0" } }, + { "input_bit_register_83", { "3.9.0", "5.3.0" } }, + { "input_bit_register_84", { "3.9.0", "5.3.0" } }, + { "input_bit_register_85", { "3.9.0", "5.3.0" } }, + { "input_bit_register_86", { "3.9.0", "5.3.0" } }, + { "input_bit_register_87", { "3.9.0", "5.3.0" } }, + { "input_bit_register_88", { "3.9.0", "5.3.0" } }, + { "input_bit_register_89", { "3.9.0", "5.3.0" } }, + { "input_bit_register_90", { "3.9.0", "5.3.0" } }, + { "input_bit_register_91", { "3.9.0", "5.3.0" } }, + { "input_bit_register_92", { "3.9.0", "5.3.0" } }, + { "input_bit_register_93", { "3.9.0", "5.3.0" } }, + { "input_bit_register_94", { "3.9.0", "5.3.0" } }, + { "input_bit_register_95", { "3.9.0", "5.3.0" } }, + { "input_bit_register_96", { "3.9.0", "5.3.0" } }, + { "input_bit_register_97", { "3.9.0", "5.3.0" } }, + { "input_bit_register_98", { "3.9.0", "5.3.0" } }, + { "input_bit_register_99", { "3.9.0", "5.3.0" } }, + { "input_bit_register_100", { "3.9.0", "5.3.0" } }, + { "input_bit_register_101", { "3.9.0", "5.3.0" } }, + { "input_bit_register_102", { "3.9.0", "5.3.0" } }, + { "input_bit_register_103", { "3.9.0", "5.3.0" } }, + { "input_bit_register_104", { "3.9.0", "5.3.0" } }, + { "input_bit_register_105", { "3.9.0", "5.3.0" } }, + { "input_bit_register_106", { "3.9.0", "5.3.0" } }, + { "input_bit_register_107", { "3.9.0", "5.3.0" } }, + { "input_bit_register_108", { "3.9.0", "5.3.0" } }, + { "input_bit_register_109", { "3.9.0", "5.3.0" } }, + { "input_bit_register_110", { "3.9.0", "5.3.0" } }, + { "input_bit_register_111", { "3.9.0", "5.3.0" } }, + { "input_bit_register_112", { "3.9.0", "5.3.0" } }, + { "input_bit_register_113", { "3.9.0", "5.3.0" } }, + { "input_bit_register_114", { "3.9.0", "5.3.0" } }, + { "input_bit_register_115", { "3.9.0", "5.3.0" } }, + { "input_bit_register_116", { "3.9.0", "5.3.0" } }, + { "input_bit_register_117", { "3.9.0", "5.3.0" } }, + { "input_bit_register_118", { "3.9.0", "5.3.0" } }, + { "input_bit_register_119", { "3.9.0", "5.3.0" } }, + { "input_bit_register_120", { "3.9.0", "5.3.0" } }, + { "input_bit_register_121", { "3.9.0", "5.3.0" } }, + { "input_bit_register_122", { "3.9.0", "5.3.0" } }, + { "input_bit_register_123", { "3.9.0", "5.3.0" } }, + { "input_bit_register_124", { "3.9.0", "5.3.0" } }, + { "input_bit_register_125", { "3.9.0", "5.3.0" } }, + { "input_bit_register_126", { "3.9.0", "5.3.0" } }, + { "input_bit_register_127", { "3.9.0", "5.3.0" } }, + { "input_double_register_0", { "3.4.0", std::nullopt } }, + { "input_double_register_1", { "3.4.0", std::nullopt } }, + { "input_double_register_2", { "3.4.0", std::nullopt } }, + { "input_double_register_3", { "3.4.0", std::nullopt } }, + { "input_double_register_4", { "3.4.0", std::nullopt } }, + { "input_double_register_5", { "3.4.0", std::nullopt } }, + { "input_double_register_6", { "3.4.0", std::nullopt } }, + { "input_double_register_7", { "3.4.0", std::nullopt } }, + { "input_double_register_8", { "3.4.0", std::nullopt } }, + { "input_double_register_9", { "3.4.0", std::nullopt } }, + { "input_double_register_10", { "3.4.0", std::nullopt } }, + { "input_double_register_11", { "3.4.0", std::nullopt } }, + { "input_double_register_12", { "3.4.0", std::nullopt } }, + { "input_double_register_13", { "3.4.0", std::nullopt } }, + { "input_double_register_14", { "3.4.0", std::nullopt } }, + { "input_double_register_15", { "3.4.0", std::nullopt } }, + { "input_double_register_16", { "3.4.0", std::nullopt } }, + { "input_double_register_17", { "3.4.0", std::nullopt } }, + { "input_double_register_18", { "3.4.0", std::nullopt } }, + { "input_double_register_19", { "3.4.0", std::nullopt } }, + { "input_double_register_20", { "3.4.0", std::nullopt } }, + { "input_double_register_21", { "3.4.0", std::nullopt } }, + { "input_double_register_22", { "3.4.0", std::nullopt } }, + { "input_double_register_23", { "3.4.0", std::nullopt } }, + { "input_double_register_24", { "3.9.0", "5.3.0" } }, + { "input_double_register_25", { "3.9.0", "5.3.0" } }, + { "input_double_register_26", { "3.9.0", "5.3.0" } }, + { "input_double_register_27", { "3.9.0", "5.3.0" } }, + { "input_double_register_28", { "3.9.0", "5.3.0" } }, + { "input_double_register_29", { "3.9.0", "5.3.0" } }, + { "input_double_register_30", { "3.9.0", "5.3.0" } }, + { "input_double_register_31", { "3.9.0", "5.3.0" } }, + { "input_double_register_32", { "3.9.0", "5.3.0" } }, + { "input_double_register_33", { "3.9.0", "5.3.0" } }, + { "input_double_register_34", { "3.9.0", "5.3.0" } }, + { "input_double_register_35", { "3.9.0", "5.3.0" } }, + { "input_double_register_36", { "3.9.0", "5.3.0" } }, + { "input_double_register_37", { "3.9.0", "5.3.0" } }, + { "input_double_register_38", { "3.9.0", "5.3.0" } }, + { "input_double_register_39", { "3.9.0", "5.3.0" } }, + { "input_double_register_40", { "3.9.0", "5.3.0" } }, + { "input_double_register_41", { "3.9.0", "5.3.0" } }, + { "input_double_register_42", { "3.9.0", "5.3.0" } }, + { "input_double_register_43", { "3.9.0", "5.3.0" } }, + { "input_double_register_44", { "3.9.0", "5.3.0" } }, + { "input_double_register_45", { "3.9.0", "5.3.0" } }, + { "input_double_register_46", { "3.9.0", "5.3.0" } }, + { "input_double_register_47", { "3.9.0", "5.3.0" } }, + { "tool_output_mode", { std::nullopt, std::nullopt } }, + { "tool_digital_output0_mode", { std::nullopt, std::nullopt } }, + { "tool_digital_output1_mode", { std::nullopt, std::nullopt } }, + { "payload", { "3.11.0", "5.5.1" } }, + { "payload_cog", { "3.11.0", "5.5.1" } }, + { "payload_inertia", { std::nullopt, std::nullopt } }, + { "script_control_line", { std::nullopt, std::nullopt } }, + { "ft_raw_wrench", { "5.9.0", "5.9.0" } }, + { "joint_position_deviation_ratio", { std::nullopt, std::nullopt } }, + { "collision_detection_ratio", { "5.15.0", "5.15.0" } }, + { "time_scale_source", { "5.17.0", "5.17.0" } } +}; + class RTDEClientTest : public ::testing::Test { protected: @@ -51,6 +406,22 @@ class RTDEClientTest : public ::testing::Test std::this_thread::sleep_for(std::chrono::seconds(1)); } + void filterOutputRecipeToBeCompatibleWith(std::vector& output_recipe, VersionInformation sw_version) + { + const auto get_min_version = [&sw_version](const std::string& output_name) -> std::optional { + return sw_version.isESeries() ? EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.at(output_name).second : + EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.at(output_name).first; + }; + const auto output_incompatible_with_version = [get_min_version, + &sw_version](const std::string& output_name) -> bool { + const auto min_version = get_min_version(output_name); + return min_version.has_value() && sw_version < VersionInformation::fromString(min_version.value()); + }; + + output_recipe.erase(std::remove_if(output_recipe.begin(), output_recipe.end(), output_incompatible_with_version), + output_recipe.end()); + } + std::string output_recipe_file_ = "resources/rtde_output_recipe.txt"; std::string input_recipe_file_ = "resources/rtde_input_recipe.txt"; comm::INotifier notifier_; @@ -362,6 +733,42 @@ TEST_F(RTDEClientTest, connect_non_running_robot) EXPECT_LT(elapsed, 2 * comm::TCPSocket::DEFAULT_RECONNECTION_TIME); } +TEST_F(RTDEClientTest, check_all_rtde_output_variables_exist) +{ + client_->init(); + + // Create an output recipe as exhaustive as possible but compatible with the current version + std::vector exhaustive_compatible_output_recipe; + + const VersionInformation sw_version = client_->getVersion(); + std::transform( + EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.begin(), EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.end(), + std::back_inserter(exhaustive_compatible_output_recipe), + [](OutputNamesWithCompatibility::const_reference data_name) -> std::string { return data_name.first; }); + filterOutputRecipeToBeCompatibleWith(exhaustive_compatible_output_recipe, sw_version); + + client_.reset(new rtde_interface::RTDEClient(ROBOT_IP, notifier_, exhaustive_compatible_output_recipe, + resources_input_recipe_)); + + EXPECT_NO_THROW(client_->init()); + client_->start(); + + // Test that we can receive and parse the timestamp from the received package to prove the setup was successful + const std::chrono::milliseconds read_timeout{ 100 }; + std::unique_ptr data_pkg = client_->getDataPackage(read_timeout); + + if (data_pkg == nullptr) + { + std::cout << "Failed to get data package from robot" << std::endl; + GTEST_FAIL(); + } + + double timestamp; + EXPECT_TRUE(data_pkg->getData("timestamp", timestamp)); + + client_->pause(); +} + int main(int argc, char* argv[]) { ::testing::InitGoogleTest(&argc, argv);