From 3769c90c34937e91e4da552c393159d5063e443e Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Mon, 23 Oct 2023 07:52:11 +0000 Subject: [PATCH] Default to non_blocking_read=true Since non-blocking-read showed significantly more stable behavior, we should default to that. --- urdf/ur.ros2_control.xacro | 2 +- urdf/ur_macro.xacro | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/urdf/ur.ros2_control.xacro b/urdf/ur.ros2_control.xacro index 801694f..98f7047 100644 --- a/urdf/ur.ros2_control.xacro +++ b/urdf/ur.ros2_control.xacro @@ -19,7 +19,7 @@ reverse_ip:=0.0.0.0 script_command_port:=50004 trajectory_port:=50003 - non_blocking_read:=false + non_blocking_read:=true keep_alive_count:=2 "> diff --git a/urdf/ur_macro.xacro b/urdf/ur_macro.xacro index 4cdd48a..b418d12 100644 --- a/urdf/ur_macro.xacro +++ b/urdf/ur_macro.xacro @@ -90,7 +90,7 @@ reverse_ip:=0.0.0.0 script_command_port:=50004 trajectory_port:=50003 - non_blocking_read:=false + non_blocking_read:=true keep_alive_count:=2" >