Skip to content

Commit 179dd05

Browse files
committed
Merge branch 'master' into force_mode_arguments
1 parent a7926d4 commit 179dd05

File tree

6 files changed

+433
-4
lines changed

6 files changed

+433
-4
lines changed

.github/workflows/ci.yml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,12 @@ jobs:
2121
ROBOT_MODEL: 'ur5e'
2222
URSIM_VERSION: '5.9.4'
2323
PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series'
24+
- DOCKER_RUN_OPTS: --network ursim_net
25+
BEFORE_INIT: 'apt-get update -qq && apt-get install -y iproute2 iputils-ping && ip addr && ping -c5 192.168.56.101'
26+
CTEST_OUTPUT_ON_FAILURE: 1
27+
ROBOT_MODEL: 'ur20'
28+
URSIM_VERSION: 'latest'
29+
PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series'
2430

2531
steps:
2632
- uses: actions/checkout@v1

README.md

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,11 @@ A C++ library for accessing Universal Robots interfaces. With this library C++-b
44
implemented in order to create external applications leveraging the versatility of Universal Robots
55
robotic manipulators.
66

7+
<!-- markdownlint-disable MD033 -->
8+
<div align="center">
9+
<img src="doc/resources/family_photo.png" alt="Universal Robot family" style="width: 90%;"/>
10+
</div>
11+
712
## Requirements
813

914
* **Polyscope** (The software running on the robot controller) version **3.14.3** (for CB3-Series),

doc/resources/family_photo.png

195 KB
Loading

src/rtde/data_package.cpp

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,8 @@ std::unordered_map<std::string, DataPackage::_rtde_type_variant> DataPackage::g_
4242
{ "target_moment", vector6d_t() },
4343
{ "actual_q", vector6d_t() },
4444
{ "actual_qd", vector6d_t() },
45-
{ "actual_qdd", vector6d_t() },
4645
{ "actual_current", vector6d_t() },
47-
{ "actual_moment", vector6d_t() },
46+
{ "actual_current_window", vector6d_t() },
4847
{ "joint_control_output", vector6d_t() },
4948
{ "actual_TCP_pose", vector6d_t() },
5049
{ "actual_TCP_speed", vector6d_t() },
@@ -57,6 +56,7 @@ std::unordered_map<std::string, DataPackage::_rtde_type_variant> DataPackage::g_
5756
{ "robot_mode", int32_t() },
5857
{ "joint_mode", vector6int32_t() },
5958
{ "safety_mode", int32_t() },
59+
{ "safety_status", int32_t() },
6060
{ "actual_tool_accelerometer", vector3d_t() },
6161
{ "speed_scaling", double() },
6262
{ "target_speed_fraction", double() },
@@ -88,7 +88,7 @@ std::unordered_map<std::string, DataPackage::_rtde_type_variant> DataPackage::g_
8888
{ "tool_output_voltage", int32_t() },
8989
{ "tool_output_current", double() },
9090
{ "tool_temperature", double() },
91-
{ "tool_force_scalar", double() },
91+
{ "tcp_force_scalar", double() },
9292
{ "output_bit_registers0_to_31", uint32_t() },
9393
{ "output_bit_registers32_to_63", uint32_t() },
9494
{ "output_bit_register_0", bool() },
@@ -548,7 +548,18 @@ std::unordered_map<std::string, DataPackage::_rtde_type_variant> DataPackage::g_
548548
{ "configurable_digital_output_mask", uint8_t() },
549549
{ "configurable_digital_output", uint8_t() },
550550
{ "tool_digital_output_mask", uint8_t() },
551+
{ "tool_output_mode", uint8_t() },
552+
{ "tool_digital_output0_mode", uint8_t() },
553+
{ "tool_digital_output1_mode", uint8_t() },
551554
{ "tool_digital_output", uint8_t() },
555+
{ "payload", double() },
556+
{ "payload_cog", vector3d_t() },
557+
{ "payload_inertia", vector6d_t() },
558+
{ "script_control_line", uint32_t() },
559+
{ "ft_raw_wrench", vector6d_t() },
560+
{ "joint_position_deviation_ratio", double() },
561+
{ "collision_detection_ratio", double() },
562+
{ "time_scale_source", int32_t() },
552563
{ "standard_analog_output_mask", uint8_t() },
553564
{ "standard_analog_output_type", uint8_t() },
554565
{ "standard_analog_output_0", double() },

src/rtde/rtde_client.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -254,7 +254,7 @@ void RTDEClient::setupOutputs(const uint16_t protocol_version)
254254
unsigned int num_retries = 0;
255255
size_t size;
256256
size_t written;
257-
uint8_t buffer[4096];
257+
uint8_t buffer[8192];
258258
URCL_LOG_INFO("Setting up RTDE communication with frequency %f", target_frequency_);
259259
if (protocol_version == 2)
260260
{

0 commit comments

Comments
 (0)