From cda979654c1056b65b3f5b72d93a91171c3b83fa Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 6 Jan 2023 18:57:06 +0000 Subject: [PATCH 01/14] Add an example with a passive joint --- README.md | 13 +++ .../launch/pendulum_example_effort.launch.py | 86 ++++++++++++++ .../pendulum_example_position.launch.py | 87 ++++++++++++++ .../urdf/test_pendulum_effort.xacro.urdf | 108 ++++++++++++++++++ .../urdf/test_pendulum_position.xacro.urdf | 108 ++++++++++++++++++ 5 files changed, 402 insertions(+) create mode 100644 gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py create mode 100644 gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py create mode 100644 gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf create mode 100644 gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf diff --git a/README.md b/README.md index 39a5ef09..26138ad8 100644 --- a/README.md +++ b/README.md @@ -254,6 +254,19 @@ Send example commands: ros2 run gazebo_ros2_control_demos example_gripper ``` +The following example shows a cart with a pendulum arm. This uses the effort command interface for the cart's degree of freedom on the rail, and the physics of the passive joint of the pendulum is solved correctly. +```bash +ros2 launch gazebo_ros2_control_demos pendulum_example_effort.launch.py +ros2 run gazebo_ros2_control_demos example_effort +``` +*Attention*: If the position or velocity command interface is used instead, the motion of the pendulum is not calculated correctly and does not move at all, see the following example. This also holds true if a mimicked joint with position or velocity interface is used. +```bash +ros2 launch gazebo_ros2_control_demos pendulum_example_position.launch.py +ros2 run gazebo_ros2_control_demos example_position +``` + + + #### Gazebo + Moveit2 + ROS 2 This example works with [ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/). diff --git a/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py new file mode 100644 index 00000000..41dd5428 --- /dev/null +++ b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py @@ -0,0 +1,86 @@ +# Copyright 2020 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + + +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch.event_handlers import OnProcessExit +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + +import xacro + + +def generate_launch_description(): + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']), + ) + + gazebo_ros2_control_demos_path = os.path.join( + get_package_share_directory('gazebo_ros2_control_demos')) + + xacro_file = os.path.join(gazebo_ros2_control_demos_path, + 'urdf', + 'test_pendulum_effort.xacro.urdf') + + doc = xacro.parse(open(xacro_file)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + output='screen', + parameters=[params] + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', 'cartpole'], + output='screen') + + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controllers'], + output='screen' + ) + + return LaunchDescription([ + RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ), + RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ), + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) diff --git a/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py b/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py new file mode 100644 index 00000000..6a370948 --- /dev/null +++ b/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py @@ -0,0 +1,87 @@ +# Copyright 2020 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + + +from launch import LaunchDescription +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler +from launch.event_handlers import OnProcessExit +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + +import xacro + + +def generate_launch_description(): + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']), + ) + + gazebo_ros2_control_demos_path = os.path.join( + get_package_share_directory('gazebo_ros2_control_demos')) + + xacro_file = os.path.join(gazebo_ros2_control_demos_path, + 'urdf', + 'test_pendulum_position.xacro.urdf') + + doc = xacro.parse(open(xacro_file)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + output='screen', + parameters=[params] + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', 'cartpole'], + output='screen') + + load_joint_state_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + load_joint_trajectory_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_trajectory_controller'], + output='screen' + ) + + return LaunchDescription([ + RegisterEventHandler( + event_handler=OnProcessExit( + target_action=spawn_entity, + on_exit=[load_joint_state_controller], + ) + ), + RegisterEventHandler( + event_handler=OnProcessExit( + target_action=load_joint_state_controller, + on_exit=[load_joint_trajectory_controller], + ) + ), + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf new file mode 100644 index 00000000..a428fd32 --- /dev/null +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf @@ -0,0 +1,108 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + gazebo_ros2_control/GazeboSystem + + + + -1000 + 1000 + + + 1.0 + + + + + + + + 1.57 + + + + + + + + + $(find gazebo_ros2_control_demos)/config/cartpole_controller_effort.yaml + + + diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf new file mode 100644 index 00000000..ae2a9112 --- /dev/null +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf @@ -0,0 +1,108 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + gazebo_ros2_control/GazeboSystem + + + + -15 + 15 + + + 1.0 + + + + + + + + 1.57 + + + + + + + + + $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml + + + From 232ac7d34983e0b522e8fbef5529f172a3f109f7 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Mon, 9 Jan 2023 17:42:42 +0000 Subject: [PATCH 02/14] Fix copyright --- .../launch/pendulum_example_effort.launch.py | 2 +- .../launch/pendulum_example_position.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py index 41dd5428..a2d6877f 100644 --- a/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py +++ b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py @@ -1,4 +1,4 @@ -# Copyright 2020 Open Source Robotics Foundation, Inc. +# Copyright 2023 Open Source Robotics Foundation, Inc. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. diff --git a/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py b/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py index 6a370948..6ec942ef 100644 --- a/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py +++ b/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py @@ -1,4 +1,4 @@ -# Copyright 2020 Open Source Robotics Foundation, Inc. +# Copyright 2023 Open Source Robotics Foundation, Inc. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. From 25895128422717e436c39c8ebda1c4161437cea5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 9 Jan 2023 18:44:03 +0100 Subject: [PATCH 03/14] Update README.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero --- README.md | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/README.md b/README.md index 26138ad8..8a168b12 100644 --- a/README.md +++ b/README.md @@ -254,16 +254,11 @@ Send example commands: ros2 run gazebo_ros2_control_demos example_gripper ``` -The following example shows a cart with a pendulum arm. This uses the effort command interface for the cart's degree of freedom on the rail, and the physics of the passive joint of the pendulum is solved correctly. +The following example shows a cart with a pendulum arm. This uses the effort command interface for the cart's +degree of freedom on the rail, and the physics of the passive joint of the pendulum is solved correctly. ```bash ros2 launch gazebo_ros2_control_demos pendulum_example_effort.launch.py ros2 run gazebo_ros2_control_demos example_effort -``` -*Attention*: If the position or velocity command interface is used instead, the motion of the pendulum is not calculated correctly and does not move at all, see the following example. This also holds true if a mimicked joint with position or velocity interface is used. -```bash -ros2 launch gazebo_ros2_control_demos pendulum_example_position.launch.py -ros2 run gazebo_ros2_control_demos example_position -``` From 4179dd6d606927e12642d31d1e86bddc66e7b1a0 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 11 Aug 2023 13:35:25 +0000 Subject: [PATCH 04/14] Fix inertias by introducing a macro --- .../urdf/test_pendulum_effort.xacro.urdf | 84 +++++++++---------- 1 file changed, 42 insertions(+), 42 deletions(-) diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf index a428fd32..9c78a9ba 100644 --- a/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf @@ -1,10 +1,36 @@ - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -20,59 +46,33 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + - + + - + - - + + @@ -93,7 +93,7 @@ - 1.57 + From 4e39ac57a1ceb6dc756f195ae87b4997ff7c2729 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 11 Aug 2023 13:54:43 +0000 Subject: [PATCH 05/14] Fix origin in macro and set some damping --- .../urdf/test_pendulum_effort.xacro.urdf | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf index 9c78a9ba..013e9a1d 100644 --- a/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf @@ -7,7 +7,7 @@ - + @@ -68,11 +68,11 @@ - + - + From c043d8007e87eeac910048b7fd24598355cbf0c1 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 11 Aug 2023 14:04:58 +0000 Subject: [PATCH 06/14] Enable passive joints again (fix #219) --- gazebo_ros2_control/src/gazebo_system.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index f659f7f3..216de505 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -608,9 +608,6 @@ hardware_interface::return_type GazeboSystem::write( this->dataPtr->sim_joints_[j]->SetVelocity(0, this->dataPtr->joint_velocity_cmd_[j]); } else if (this->dataPtr->joint_control_methods_[j] & EFFORT) { // NOLINT this->dataPtr->sim_joints_[j]->SetForce(0, this->dataPtr->joint_effort_cmd_[j]); - } else { - // Fallback case is a velocity command of zero - this->dataPtr->sim_joints_[j]->SetVelocity(0, 0.0); } } } From d3d1f608bddc4933eba1f35e5844dd081b1d668d Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Tue, 15 Aug 2023 09:13:55 +0000 Subject: [PATCH 07/14] Format code --- doc/index.rst | 1 - 1 file changed, 1 deletion(-) diff --git a/doc/index.rst b/doc/index.rst index 503b6b8e..0ef3dd88 100644 --- a/doc/index.rst +++ b/doc/index.rst @@ -314,4 +314,3 @@ degree of freedom on the rail, and the physics of the passive joint of the pendu ros2 launch gazebo_ros2_control_demos pendulum_example_position.launch.py ros2 run gazebo_ros2_control_demos example_position - From 7d22e1b136c4cbc17ff155a5f12c96427a0f2b0e Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Mon, 2 Oct 2023 14:36:14 +0000 Subject: [PATCH 08/14] Fix launch file --- .../launch/pendulum_example_effort.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py index a2d6877f..d630af63 100644 --- a/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py +++ b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py @@ -63,7 +63,7 @@ def generate_launch_description(): ) load_joint_trajectory_controller = ExecuteProcess( - cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controllers'], + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controller'], output='screen' ) From a0adfe3099ce12ce27eb2a592e7d31d12c193139 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Mon, 2 Oct 2023 14:36:28 +0000 Subject: [PATCH 09/14] Update urdf --- .../urdf/test_pendulum_position.xacro.urdf | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf index ae2a9112..0231e152 100644 --- a/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf @@ -1,8 +1,4 @@ - - - - @@ -93,7 +89,7 @@ - 1.57 + From 2da9fa9a51a474ba5e85dc131dafdd6efff551af Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 13 Nov 2023 22:13:47 +0100 Subject: [PATCH 10/14] Update doc/index.rst --- doc/index.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/index.rst b/doc/index.rst index 0ef3dd88..e619a958 100644 --- a/doc/index.rst +++ b/doc/index.rst @@ -308,7 +308,7 @@ degree of freedom on the rail, and the physics of the passive joint of the pendu .. note:: - If the position or velocity command interface is used instead, the motion of the pendulum is not calculated correctly and does not move at all, see the following example. This also holds true if a mimicked joint with position or velocity interface is used. + If the position command interface is used instead, the motion of the pendulum is not calculated correctly and does not move at all, see the following example. This also holds true if a mimicked joint with position interface is used. .. code-block:: shell From d89020caceb10fe3545edf273aac1ddf292fe657 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Thu, 25 Apr 2024 15:11:20 +0000 Subject: [PATCH 11/14] Add link to PR. --- doc/index.rst | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/doc/index.rst b/doc/index.rst index be9db697..21d9e9cc 100644 --- a/doc/index.rst +++ b/doc/index.rst @@ -305,9 +305,9 @@ degree of freedom on the rail, and the physics of the passive joint of the pendu .. note:: - If the position command interface is used instead, the motion of the pendulum is not calculated correctly and does not move at all, see the following example. This also holds true if a mimicked joint with position interface is used. + If the position command interface is used instead, the motion of the pendulum is not calculated correctly and does not move at all, see this `PR `__. This also holds true if a mimicked joint with position interface is used. To demonstrate this, run -.. code-block:: shell + .. code-block:: shell - ros2 launch gazebo_ros2_control_demos pendulum_example_position.launch.py - ros2 run gazebo_ros2_control_demos example_position + ros2 launch gazebo_ros2_control_demos pendulum_example_position.launch.py + ros2 run gazebo_ros2_control_demos example_position From e3bb11cd6359bad167d873bd6e21f14b7d2cfaf4 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Thu, 25 Apr 2024 15:13:15 +0000 Subject: [PATCH 12/14] Update copyright --- .../launch/pendulum_example_effort.launch.py | 2 +- .../launch/pendulum_example_position.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py index d630af63..059028ee 100644 --- a/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py +++ b/gazebo_ros2_control_demos/launch/pendulum_example_effort.launch.py @@ -1,4 +1,4 @@ -# Copyright 2023 Open Source Robotics Foundation, Inc. +# Copyright 2024 ros2_control Development Team # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. diff --git a/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py b/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py index 6ec942ef..4932b4f3 100644 --- a/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py +++ b/gazebo_ros2_control_demos/launch/pendulum_example_position.launch.py @@ -1,4 +1,4 @@ -# Copyright 2023 Open Source Robotics Foundation, Inc. +# Copyright 2024 ros2_control Development Team # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. From b493c12622be9f37a6b7859865e7545e39b5c4ac Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Fri, 26 Apr 2024 10:03:40 +0200 Subject: [PATCH 13/14] Apply suggestions from code review MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero --- gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf | 2 +- .../urdf/test_pendulum_position.xacro.urdf | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf index 013e9a1d..bd3c18ff 100644 --- a/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_effort.xacro.urdf @@ -102,7 +102,7 @@ - $(find gazebo_ros2_control_demos)/config/cartpole_controller_effort.yaml + $(find gazebo_ros2_control_demos)/config/cart_controller_effort.yaml diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf index 0231e152..ab0b11ea 100644 --- a/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf @@ -98,7 +98,7 @@ - $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml + $(find gazebo_ros2_control_demos)/config/cart_controller.yaml From 782a4a1c57f84dc5258149b18eb3d87b59e5e281 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Mon, 29 Apr 2024 12:43:35 +0000 Subject: [PATCH 14/14] Adapt URDF to match the effort one --- .../urdf/test_pendulum_position.xacro.urdf | 78 ++++++++++--------- 1 file changed, 41 insertions(+), 37 deletions(-) diff --git a/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf index ab0b11ea..185cd26b 100644 --- a/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_pendulum_position.xacro.urdf @@ -1,6 +1,36 @@ - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -16,59 +46,33 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + - + + - + - - + +