From b8986c0b2da0c5649b312aee2c2df48366af2950 Mon Sep 17 00:00:00 2001 From: Emmanuel Akita <61601578+EAkita@users.noreply.github.com> Date: Thu, 26 Oct 2023 12:28:49 -0500 Subject: [PATCH] Fixed hardware interface initialization (#14) ### Description * Updated the launch file parameters to correctly initialize the hardware interface, as seen in the 2 images below. The first is before the change, and the second is after the change. ![Before_change](https://github.com/gbartyzel/ros2_net_ft_driver/assets/61601578/a2f36a3b-ae50-41a5-baa8-c209f60fa21e) ![After_change](https://github.com/gbartyzel/ros2_net_ft_driver/assets/61601578/abd715ce-9655-403e-b6c3-4a778010bc21) * Updated the README file to reflect new ATI Net F/T testing ### How I Tested I successfully launched and echoed the /force_torque_sensor_broadcaster/wrench. --- README.md | 3 +-- net_ft_driver/launch/net_ft_broadcaster.launch.py | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 5f6be3a..d57df90 100644 --- a/README.md +++ b/README.md @@ -14,8 +14,7 @@ Currently this package supports only following F/T sensors: - ATI AXIA series - ATI Net F/T series -Software was tested with `ATI AXIA80` and `OnRobot HEX-E V2`. Tests on ATI Net F/T -series sensor are needed. +Software was tested with `ATI AXIA80` and `OnRobot HEX-E V2` and `ATI Net F/T series`. ## Installation diff --git a/net_ft_driver/launch/net_ft_broadcaster.launch.py b/net_ft_driver/launch/net_ft_broadcaster.launch.py index 5d5879c..4f050ee 100644 --- a/net_ft_driver/launch/net_ft_broadcaster.launch.py +++ b/net_ft_driver/launch/net_ft_broadcaster.launch.py @@ -149,7 +149,7 @@ def generate_launch_description(): declared_arguments.append( launch.actions.DeclareLaunchArgument( name="internal_filter_rate", - default_value="false", + default_value="0", description=( "The internal low pass filter rate, " "refer for specific values to the sensor manuals.", @@ -159,7 +159,7 @@ def generate_launch_description(): declared_arguments.append( launch.actions.DeclareLaunchArgument( name="use_hardware_biasing", - default_value="0", + default_value="false", description="Whether to use built-in sensor zeroing", ) )