From 8d647e6db7f9fc7fd58b45a7669adb4b1022bf01 Mon Sep 17 00:00:00 2001
From: Ventsi <uquzq@student.kit.edu>
Date: Mon, 28 Oct 2024 11:26:37 +0100
Subject: [PATCH] Change names for better understanding and remove inverse of
 simple robot

---
 .../__pycache__/iiwa.launch.cpython-310.pyc   | Bin 6485 -> 6485 bytes
 .../config/initial_positions_IRS_Lab.yaml     |  11 +-
 ...imple_robot_rviz_simulation_1dof_launch.py |  18 +-
 ...ions.rviz => simple_robot_simulation.rviz} |   0
 ros2_ws/src/simple_robot_1dof/setup.py        |   4 +-
 .../simple_robot_1dof/reference_node_1dof.py  |  11 +-
 ...de_1dof.py => transformation_node_1dof.py} |  43 ++--
 ...imple_robot_rviz_simulation_2dof_launch.py |  32 +--
 ...ions.rviz => simple_robot_simulation.rviz} |   0
 ros2_ws/src/simple_robot_2dof/setup.py        |   6 +-
 ... transformation_node_2dof_simultaneous.py} |   0
 ...=> transformation_node_2dof_successive.py} |   0
 ...imple_robot_rviz_simulation_3dof_launch.py |  25 +--
 ...ions.rviz => simple_robot_simulation.rviz} |   0
 ros2_ws/src/simple_robot_3dof/setup.py        |   7 +-
 ... transformation_node_3dof_simultaneous.py} |   2 -
 ...=> transformation_node_3dof_successive.py} |   0
 .../simple_robot_inverse_kinematik/LICENSE    | 202 ------------------
 .../package.xml                               |  41 ----
 .../resource/simple_robot_inverse_kinematik   |   0
 .../simple_robot_inverse_kinematik/setup.cfg  |   4 -
 .../simple_robot_inverse_kinematik/setup.py   |  26 ---
 .../__init__.py                               |   0
 .../inverse_kinematik.py                      |  75 -------
 .../test/test_copyright.py                    |  25 ---
 .../test/test_flake8.py                       |  25 ---
 .../test/test_pep257.py                       |  23 --
 27 files changed, 64 insertions(+), 516 deletions(-)
 rename ros2_ws/src/simple_robot_1dof/rviz/{forward_kinematics_simulations.rviz => simple_robot_simulation.rviz} (100%)
 rename ros2_ws/src/simple_robot_1dof/simple_robot_1dof/{forward_kinematics_node_1dof.py => transformation_node_1dof.py} (85%)
 rename ros2_ws/src/simple_robot_2dof/rviz/{forward_kinematics_simulations.rviz => simple_robot_simulation.rviz} (100%)
 rename ros2_ws/src/simple_robot_2dof/simple_robot_2dof/{forward_kinematics_node_2dof_1.py => transformation_node_2dof_simultaneous.py} (100%)
 rename ros2_ws/src/simple_robot_2dof/simple_robot_2dof/{forward_kinematics_node_2dof_2.py => transformation_node_2dof_successive.py} (100%)
 rename ros2_ws/src/simple_robot_3dof/rviz/{forward_kinematics_simulations.rviz => simple_robot_simulation.rviz} (100%)
 rename ros2_ws/src/simple_robot_3dof/simple_robot_3dof/{forward_kinematics_node_3dof_1.py => transformation_node_3dof_simultaneous.py} (98%)
 rename ros2_ws/src/simple_robot_3dof/simple_robot_3dof/{forward_kinematics_node_3dof_2.py => transformation_node_3dof_successive.py} (100%)
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/LICENSE
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/package.xml
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/resource/simple_robot_inverse_kinematik
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/setup.cfg
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/setup.py
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/simple_robot_inverse_kinematik/__init__.py
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/simple_robot_inverse_kinematik/inverse_kinematik.py
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/test/test_copyright.py
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/test/test_flake8.py
 delete mode 100644 ros2_ws/src/simple_robot_inverse_kinematik/test/test_pep257.py

diff --git a/ros2_ws/src/iiwa/iiwa_bringup/launch/__pycache__/iiwa.launch.cpython-310.pyc b/ros2_ws/src/iiwa/iiwa_bringup/launch/__pycache__/iiwa.launch.cpython-310.pyc
index 4c1b605ea40d27a2054ae612367db50df44724be..2117a20787616705932d3d62525753ac79c5811b 100644
GIT binary patch
delta 21
ccmca=bk&F_pO=@5fq{Xcy;LrJBaf#f06;YbP5=M^

delta 21
ccmca=bk&F_pO=@5fq{V`ymNcnMjlT|07B9Q$^ZZW

diff --git a/ros2_ws/src/iiwa/iiwa_description/config/initial_positions_IRS_Lab.yaml b/ros2_ws/src/iiwa/iiwa_description/config/initial_positions_IRS_Lab.yaml
index f26e74a..157af1e 100644
--- a/ros2_ws/src/iiwa/iiwa_description/config/initial_positions_IRS_Lab.yaml
+++ b/ros2_ws/src/iiwa/iiwa_description/config/initial_positions_IRS_Lab.yaml
@@ -1,7 +1,7 @@
 # Default initial positions for the panda arm's ros2_control fake system
 initial_positions:
 # Default initial positions for the panda arm's ros2_control fake system
-initial_positions:
+initial_positions:  
   joint_a1: 2.97923
   joint_a2: 1.42580
   joint_a3: 0.02157
@@ -10,12 +10,3 @@ initial_positions:
   joint_a6: 1.72062
   joint_a7: 0.01032
 
-
-  #joint_a1: 2.97923
-  #joint_a2: 1.42580
-  #joint_a3: 0.02157
-  #joint_a4: 1.64101
-  #joint_a5: 0.14299
-  #joint_a6: 1.72062
-  #joint_a7: 0.01032
-
diff --git a/ros2_ws/src/simple_robot_1dof/launch/simple_robot_rviz_simulation_1dof_launch.py b/ros2_ws/src/simple_robot_1dof/launch/simple_robot_rviz_simulation_1dof_launch.py
index 8f91fe7..ebfc6d0 100644
--- a/ros2_ws/src/simple_robot_1dof/launch/simple_robot_rviz_simulation_1dof_launch.py
+++ b/ros2_ws/src/simple_robot_1dof/launch/simple_robot_rviz_simulation_1dof_launch.py
@@ -13,7 +13,7 @@ def generate_launch_description():
     rviz_config_file = os.path.join(
         get_package_share_directory(package_name),
         'rviz',
-        'forward_kinematics_simulations.rviz'
+        'simple_robot_simulation.rviz'
     )
 
     urdf_dir = os.path.join(get_package_share_directory(package_name), 'urdf')
@@ -62,10 +62,10 @@ def generate_launch_description():
     constant_speed = LaunchConfiguration('constant_speed')
 
 
-    forward_kinematics_node = Node(
+    transformation_node = Node(
             package = package_name,
-            executable = 'forward_kinematics_node_1dof',
-            name =  'forward_kinematics_node',
+            executable = 'transformation_node_1dof',
+            name =  'transformation_node',
             output = 'screen',
             parameters = []
         )
@@ -96,27 +96,19 @@ def generate_launch_description():
             output='screen',
             parameters = []
         )
-    simple_robot_inverse_kinematics_node = Node(
-        package='simple_robot_inverse_kinematik',
-        executable='simple_robot_inverse_kinematik',
-        name='simple_robot_inverse_kinematik',
-        parameters=[]
-    )
     robot_state_publisher = Node(
         package='robot_state_publisher',
         executable='robot_state_publisher',
         output='both',
         parameters=[
-            # {'robot_description': combined_robot_desc},
             {'robot_description': robot_desc},
             ]
     )
     nodes = [
-        forward_kinematics_node,
+        transformation_node,
         reference_node,
         rviz_node,
         kuka_inverse_kinematics_node,
-        simple_robot_inverse_kinematics_node,
         robot_state_publisher,
     ]
 
diff --git a/ros2_ws/src/simple_robot_1dof/rviz/forward_kinematics_simulations.rviz b/ros2_ws/src/simple_robot_1dof/rviz/simple_robot_simulation.rviz
similarity index 100%
rename from ros2_ws/src/simple_robot_1dof/rviz/forward_kinematics_simulations.rviz
rename to ros2_ws/src/simple_robot_1dof/rviz/simple_robot_simulation.rviz
diff --git a/ros2_ws/src/simple_robot_1dof/setup.py b/ros2_ws/src/simple_robot_1dof/setup.py
index b8d38ed..31af5a6 100644
--- a/ros2_ws/src/simple_robot_1dof/setup.py
+++ b/ros2_ws/src/simple_robot_1dof/setup.py
@@ -13,7 +13,7 @@ setup(
             ['resource/' + package_name]),
         ('share/' + package_name, ['package.xml']),
         ('share/' + package_name + '/launch', ['launch/simple_robot_rviz_simulation_1dof_launch.py']),
-        ('share/' + package_name + '/rviz', ['rviz/forward_kinematics_simulations.rviz']),
+        ('share/' + package_name + '/rviz', ['rviz/simple_robot_simulation.rviz']),
         (os.path.join('share', package_name, 'urdf'), glob('urdf/*.urdf')),
         (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))),
     ],
@@ -26,7 +26,7 @@ setup(
     tests_require=['pytest'],
     entry_points={
         'console_scripts': [
-            'forward_kinematics_node_1dof = simple_robot_1dof.forward_kinematics_node_1dof:main',
+            'transformation_node_1dof = simple_robot_1dof.transformation_node_1dof:main',
             'reference_node_1dof = simple_robot_1dof.reference_node_1dof:main',
         ],
     },
diff --git a/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/reference_node_1dof.py b/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/reference_node_1dof.py
index a041859..ae2fae9 100644
--- a/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/reference_node_1dof.py
+++ b/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/reference_node_1dof.py
@@ -2,8 +2,6 @@ import rclpy
 from rclpy.node import Node
 import numpy as np
 from std_msgs.msg import Float64
-from geometry_msgs.msg import Point, PoseStamped
-import time
 
 
 class Reference_Node_1DoF(Node):
@@ -27,12 +25,15 @@ class Reference_Node_1DoF(Node):
         self.velocity_constant = self.get_parameter('velocity_constant').get_parameter_value().double_value
         self.constant_speed = self.get_parameter('constant_speed').get_parameter_value().bool_value
 
-        self.index = 0
+        # min. and max. values of parameter k
         self.k_start = 0.0
         self.k_end = 1.0
         self.k = self.k_start
+        # variable for the velocity
         self.current_velocity = 0.0
+        # faktor for the decelaration phase
         self.faktor = 1.3
+        # timer period and timer
         self.timer_period = 0.1  # seconds
         self.timer = self.create_timer(self.timer_period, self.ref_point_publisher)
         # List the points
@@ -63,10 +64,10 @@ class Reference_Node_1DoF(Node):
                 self.k = self.k + self.current_velocity
 
         #setting back to 0
-        if self.k>self.k_end:
+        if self.k > self.k_end:
             self.k = self.k_start
             self.current_velocity = 0.0
-            self.index += 1
+
 
         msg.data = self.k
         self.publisher_.publish(msg)
diff --git a/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/forward_kinematics_node_1dof.py b/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/transformation_node_1dof.py
similarity index 85%
rename from ros2_ws/src/simple_robot_1dof/simple_robot_1dof/forward_kinematics_node_1dof.py
rename to ros2_ws/src/simple_robot_1dof/simple_robot_1dof/transformation_node_1dof.py
index fb4e211..97c36ca 100644
--- a/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/forward_kinematics_node_1dof.py
+++ b/ros2_ws/src/simple_robot_1dof/simple_robot_1dof/transformation_node_1dof.py
@@ -10,14 +10,16 @@ from std_msgs.msg import Float64
 from nav_msgs.msg import Path
 from geometry_msgs.msg import PoseStamped
 from geometry_msgs.msg import Pose
+from sensor_msgs.msg import JointState
 from visualization_msgs.msg import Marker
 from scipy.spatial.transform import Rotation
+from rclpy.clock import Clock
 
 
-class Forward_Kinematics_Node_1Dof(Node):
+class Transformation_Node_1Dof(Node):
 
     def __init__(self):
-        super().__init__('forward_kinematics_node_1dof')
+        super().__init__('transformation_node_1dof')
         self.subscription = self.create_subscription(
             Float64,
             '/dof1/reference_angles',
@@ -47,7 +49,7 @@ class Forward_Kinematics_Node_1Dof(Node):
         # publishers
         self.path_publisher_ = self.create_publisher(Path, '/simple_robot/visualization_path', 10)
         self.point_publisher_ = self.create_publisher(Marker, '/simple_robot/visualization_marker', 10)
-        self.pose_publisher_simple_robot_ = self.create_publisher(Pose, '/simple_robot/target_pose', 10)
+        self.joint_state_publisher_simple_robot_ = self.create_publisher(JointState, '/joint_states', 10)
         self.pose_publisher_kuka_robot_ = self.create_publisher(Pose, '/kuka_iiwa/target_pose', 10)
         self.velocity_pub = self.create_publisher(Float64, '/velocity', 10)
 
@@ -91,9 +93,10 @@ class Forward_Kinematics_Node_1Dof(Node):
         end_forward_kinematics_simple = np.matmul(self.intermediate_rotation, start_forward_kinematics_simple)
         # get the desired position and orientation
         end_position_simple = end_forward_kinematics_simple[:4, 3]
-        end_orientation_simple = Rotation.from_matrix(end_forward_kinematics_simple[:3, :3]).as_quat()
-        # call the funct. publishing the desired pose
-        self.publish_pose_simple_robot(end_position_simple, end_orientation_simple)
+
+        # call the function updating the state of simple robot
+        self.publish_joint_states_simple_robot()
+
         # construct path
         self.construct_path(end_position_simple)
 
@@ -160,18 +163,24 @@ class Forward_Kinematics_Node_1Dof(Node):
         self.point_publisher_.publish(marker)
 
 
-    def publish_pose_simple_robot(self, vector, quaternion):
-        pose_msg_sr = Pose()
-        pose_msg_sr.position.x = vector[0]
-        pose_msg_sr.position.y = vector[1]
-        pose_msg_sr.position.z = vector[2]
-        pose_msg_sr.orientation.x = quaternion[0]
-        pose_msg_sr.orientation.y = quaternion[1]
-        pose_msg_sr.orientation.z = quaternion[2]
-        pose_msg_sr.orientation.w = quaternion[3]
-        self.pose_publisher_simple_robot_.publish(pose_msg_sr)
+    def publish_joint_states_simple_robot(self):
+        # instead of publishing a pose, we publish the states of the joint of simple robot directly 
+        # because they are identical to the parameters theta, h, d
+        joint_names = ['joint1']
+        joint_states = [0.0]
+        joint_states[0] = self.theta_fraction
+        
+        joint_state_msg = JointState()
+        joint_state_msg.header.stamp = Clock().now().to_msg()
+
+        joint_state_msg.name = joint_names
+        joint_state_msg.position = joint_states
+
+        self.joint_state_publisher_simple_robot_.publish(joint_state_msg)
+
 
     def publish_pose_kuka_pose(self, vector, quaternion):    
+        # publish the pose of the KUKA robot
         pose_msg = Pose()
         pose_msg.position.x = vector[0]
         pose_msg.position.y = vector[1]
@@ -185,7 +194,7 @@ class Forward_Kinematics_Node_1Dof(Node):
 
 def main(args = None):
     rclpy.init(args = args)
-    node = Forward_Kinematics_Node_1Dof()
+    node = Transformation_Node_1Dof()
     rclpy.spin(node)
     node.destroy_node()
     rclpy.shutdown()
diff --git a/ros2_ws/src/simple_robot_2dof/launch/simple_robot_rviz_simulation_2dof_launch.py b/ros2_ws/src/simple_robot_2dof/launch/simple_robot_rviz_simulation_2dof_launch.py
index 3b122d4..7db61e6 100644
--- a/ros2_ws/src/simple_robot_2dof/launch/simple_robot_rviz_simulation_2dof_launch.py
+++ b/ros2_ws/src/simple_robot_2dof/launch/simple_robot_rviz_simulation_2dof_launch.py
@@ -13,7 +13,7 @@ def generate_launch_description():
     rviz_config_file = os.path.join(
         get_package_share_directory(package_name),
         'rviz',
-        'forward_kinematics_simulations.rviz'
+        'simple_robot_simulation.rviz'
     )
 
     urdf_dir = os.path.join(get_package_share_directory(package_name), 'urdf')
@@ -66,18 +66,18 @@ def generate_launch_description():
     simultaneous = LaunchConfiguration('simultaneous')
     constant_speed = LaunchConfiguration('constant_speed')
 
-    forward_kinematics_node_1 = Node(
+    tranformation_node_sim = Node(
             package = package_name,
-            executable = 'forward_kinematics_node_2dof_1',
-            name =  'forward_kinematics_node',
+            executable = 'transformation_node_2dof_sim',
+            name =  'transformation_node',
             output = 'screen',
             parameters = [],
             condition = IfCondition(simultaneous)
         )
-    forward_kinematics_node_2 = Node(
+    tranformation_node_suc = Node(
             package = package_name,
-            executable = 'forward_kinematics_node_2dof_2',
-            name =  'forward_kinematics_node',
+            executable = 'transformation_node_2dof_suc',
+            name =  'transformation_node',
             output = 'screen',
             parameters = [],
             condition = UnlessCondition(simultaneous)
@@ -110,12 +110,6 @@ def generate_launch_description():
             output='screen',
             parameters = []
         )
-    simple_robot_inverse_kinematics_node = Node(
-        package='simple_robot_inverse_kinematik',
-        executable='simple_robot_inverse_kinematik',
-        name='simple_robot_inverse_kinematik',
-        parameters=[]
-    )
     robot_state_publisher = Node(
         package='robot_state_publisher',
         executable='robot_state_publisher',
@@ -124,21 +118,13 @@ def generate_launch_description():
             {'robot_description': robot_desc}
             ]
     )
-    joint_state_publisher_gui = Node(
-        package='joint_state_publisher_gui',
-        executable='joint_state_publisher_gui',
-        name='joint_state_publisher_gui',
-        output='screen'
-    )
     
     nodes = [
-        forward_kinematics_node_1,
-        forward_kinematics_node_2,
+        tranformation_node_sim,
+        tranformation_node_suc,
         reference_node,
         rviz_node,
         inverse_kinematic_node,
-        # joint_state_publisher_gui,
-        # simple_robot_inverse_kinematics_node,
         robot_state_publisher
     ]
 
diff --git a/ros2_ws/src/simple_robot_2dof/rviz/forward_kinematics_simulations.rviz b/ros2_ws/src/simple_robot_2dof/rviz/simple_robot_simulation.rviz
similarity index 100%
rename from ros2_ws/src/simple_robot_2dof/rviz/forward_kinematics_simulations.rviz
rename to ros2_ws/src/simple_robot_2dof/rviz/simple_robot_simulation.rviz
diff --git a/ros2_ws/src/simple_robot_2dof/setup.py b/ros2_ws/src/simple_robot_2dof/setup.py
index bc62b9d..ec23714 100644
--- a/ros2_ws/src/simple_robot_2dof/setup.py
+++ b/ros2_ws/src/simple_robot_2dof/setup.py
@@ -14,7 +14,7 @@ setup(
             ['resource/' + package_name]),
         ('share/' + package_name, ['package.xml']),
         ('share/' + package_name + '/launch', ['launch/simple_robot_rviz_simulation_2dof_launch.py']),
-        ('share/' + package_name + '/rviz', ['rviz/forward_kinematics_simulations.rviz']),
+        ('share/' + package_name + '/rviz', ['rviz/simple_robot_simulation.rviz']),
         (os.path.join('share', package_name, 'urdf'), glob('urdf/*.urdf')),
         (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))),
 
@@ -29,8 +29,8 @@ setup(
     tests_require=['pytest'],
     entry_points={
         'console_scripts': [
-            'forward_kinematics_node_2dof_1 = simple_robot_2dof.forward_kinematics_node_2dof_1:main',
-            'forward_kinematics_node_2dof_2 = simple_robot_2dof.forward_kinematics_node_2dof_2:main',
+            'transformation_node_2dof_sim = simple_robot_2dof.transformation_node_2dof_simultaneous:main',
+            'transformation_node_2dof_suc = simple_robot_2dof.transformation_node_2dof_successive:main',
             'reference_node_2dof = simple_robot_2dof.reference_node_2dof:main',
         ],
     },
diff --git a/ros2_ws/src/simple_robot_2dof/simple_robot_2dof/forward_kinematics_node_2dof_1.py b/ros2_ws/src/simple_robot_2dof/simple_robot_2dof/transformation_node_2dof_simultaneous.py
similarity index 100%
rename from ros2_ws/src/simple_robot_2dof/simple_robot_2dof/forward_kinematics_node_2dof_1.py
rename to ros2_ws/src/simple_robot_2dof/simple_robot_2dof/transformation_node_2dof_simultaneous.py
diff --git a/ros2_ws/src/simple_robot_2dof/simple_robot_2dof/forward_kinematics_node_2dof_2.py b/ros2_ws/src/simple_robot_2dof/simple_robot_2dof/transformation_node_2dof_successive.py
similarity index 100%
rename from ros2_ws/src/simple_robot_2dof/simple_robot_2dof/forward_kinematics_node_2dof_2.py
rename to ros2_ws/src/simple_robot_2dof/simple_robot_2dof/transformation_node_2dof_successive.py
diff --git a/ros2_ws/src/simple_robot_3dof/launch/simple_robot_rviz_simulation_3dof_launch.py b/ros2_ws/src/simple_robot_3dof/launch/simple_robot_rviz_simulation_3dof_launch.py
index 7ccd1b0..cc642d0 100644
--- a/ros2_ws/src/simple_robot_3dof/launch/simple_robot_rviz_simulation_3dof_launch.py
+++ b/ros2_ws/src/simple_robot_3dof/launch/simple_robot_rviz_simulation_3dof_launch.py
@@ -13,7 +13,7 @@ def generate_launch_description():
     rviz_config_file = os.path.join(
         get_package_share_directory(package_name),
         'rviz',
-        'forward_kinematics_simulations.rviz'
+        'simple_robot_simulation.rviz'
     )
 
     urdf_dir = os.path.join(get_package_share_directory(package_name), 'urdf')
@@ -66,18 +66,18 @@ def generate_launch_description():
     simultaneous = LaunchConfiguration('simultaneous')
     constant_speed = LaunchConfiguration('constant_speed')
 
-    forward_kinematics_node_1 = Node(
+    transformation_node_sim = Node(
             package = package_name,
-            executable = 'forward_kinematics_node_3dof_1',
-            name =  'forward_kinematics_node',
+            executable = 'transformation_node_3dof_sim',
+            name =  'transformation_node',
             output = 'screen',
             parameters = [],
             condition = IfCondition(simultaneous)
         )
-    forward_kinematics_node_2 = Node(
+    transformation_node_suc = Node(
             package = package_name,
-            executable = 'forward_kinematics_node_3dof_2',
-            name =  'forward_kinematics_node',
+            executable = 'transformation_node_3dof_suc',
+            name =  'transformation_node',
             output = 'screen',
             parameters = [],
             condition = UnlessCondition(simultaneous)
@@ -118,21 +118,14 @@ def generate_launch_description():
             {'robot_description': robot_desc}
             ]
     )
-    joint_state_publisher_gui = Node(
-        package='joint_state_publisher_gui',
-        executable='joint_state_publisher_gui',
-        name='joint_state_publisher_gui',
-        output='screen'
-    )
     
     nodes = [
-        forward_kinematics_node_1,
-        forward_kinematics_node_2,
+        transformation_node_sim,
+        transformation_node_suc,
         reference_node,
         rviz_node,
         inverse_kinematics_node,
         robot_state_publisher,
-        # joint_state_publisher_gui
     ]
 
     return LaunchDescription(declared_arguments + nodes)
\ No newline at end of file
diff --git a/ros2_ws/src/simple_robot_3dof/rviz/forward_kinematics_simulations.rviz b/ros2_ws/src/simple_robot_3dof/rviz/simple_robot_simulation.rviz
similarity index 100%
rename from ros2_ws/src/simple_robot_3dof/rviz/forward_kinematics_simulations.rviz
rename to ros2_ws/src/simple_robot_3dof/rviz/simple_robot_simulation.rviz
diff --git a/ros2_ws/src/simple_robot_3dof/setup.py b/ros2_ws/src/simple_robot_3dof/setup.py
index 0b173fd..6d78464 100644
--- a/ros2_ws/src/simple_robot_3dof/setup.py
+++ b/ros2_ws/src/simple_robot_3dof/setup.py
@@ -13,7 +13,7 @@ setup(
             ['resource/' + package_name]),
         ('share/' + package_name, ['package.xml']),
         ('share/' + package_name + '/launch', ['launch/simple_robot_rviz_simulation_3dof_launch.py']),
-        ('share/' + package_name + '/rviz', ['rviz/forward_kinematics_simulations.rviz']),
+        ('share/' + package_name + '/rviz', ['rviz/simple_robot_simulation.rviz']),
         (os.path.join('share', package_name, 'urdf'), glob('urdf/*.urdf')),
         (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))),
     ],
@@ -26,9 +26,8 @@ setup(
     tests_require=['pytest'],
     entry_points={
         'console_scripts': [
-            'forward_kinematics_node_3dof_1 = simple_robot_3dof.forward_kinematics_node_3dof_1:main',
-            'forward_kinematics_node_3dof_2 = simple_robot_3dof.forward_kinematics_node_3dof_2:main',
-            'forward_kinematics_node_3dof_3 = simple_robot_3dof.forward_kinematics_node_3dof_3:main',
+            'transformation_node_3dof_sim = simple_robot_3dof.transformation_node_3dof_simultaneous:main',
+            'transformation_node_3dof_suc = simple_robot_3dof.transformation_node_3dof_successive:main',
             'reference_node_3dof = simple_robot_3dof.reference_node_3dof:main',
         ],
     },
diff --git a/ros2_ws/src/simple_robot_3dof/simple_robot_3dof/forward_kinematics_node_3dof_1.py b/ros2_ws/src/simple_robot_3dof/simple_robot_3dof/transformation_node_3dof_simultaneous.py
similarity index 98%
rename from ros2_ws/src/simple_robot_3dof/simple_robot_3dof/forward_kinematics_node_3dof_1.py
rename to ros2_ws/src/simple_robot_3dof/simple_robot_3dof/transformation_node_3dof_simultaneous.py
index 82c3b7c..e5a6617 100644
--- a/ros2_ws/src/simple_robot_3dof/simple_robot_3dof/forward_kinematics_node_3dof_1.py
+++ b/ros2_ws/src/simple_robot_3dof/simple_robot_3dof/transformation_node_3dof_simultaneous.py
@@ -9,9 +9,7 @@ import numpy as np
 from std_msgs.msg import Float64
 from nav_msgs.msg import Path
 from sensor_msgs.msg import JointState
-from geometry_msgs.msg import PoseStamped
 from geometry_msgs.msg import Pose
-from visualization_msgs.msg import Marker
 from scipy.spatial.transform import Rotation
 from rclpy.clock import Clock
 
diff --git a/ros2_ws/src/simple_robot_3dof/simple_robot_3dof/forward_kinematics_node_3dof_2.py b/ros2_ws/src/simple_robot_3dof/simple_robot_3dof/transformation_node_3dof_successive.py
similarity index 100%
rename from ros2_ws/src/simple_robot_3dof/simple_robot_3dof/forward_kinematics_node_3dof_2.py
rename to ros2_ws/src/simple_robot_3dof/simple_robot_3dof/transformation_node_3dof_successive.py
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/LICENSE b/ros2_ws/src/simple_robot_inverse_kinematik/LICENSE
deleted file mode 100644
index d645695..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/LICENSE
+++ /dev/null
@@ -1,202 +0,0 @@
-
-                                 Apache License
-                           Version 2.0, January 2004
-                        http://www.apache.org/licenses/
-
-   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
-
-   1. Definitions.
-
-      "License" shall mean the terms and conditions for use, reproduction,
-      and distribution as defined by Sections 1 through 9 of this document.
-
-      "Licensor" shall mean the copyright owner or entity authorized by
-      the copyright owner that is granting the License.
-
-      "Legal Entity" shall mean the union of the acting entity and all
-      other entities that control, are controlled by, or are under common
-      control with that entity. For the purposes of this definition,
-      "control" means (i) the power, direct or indirect, to cause the
-      direction or management of such entity, whether by contract or
-      otherwise, or (ii) ownership of fifty percent (50%) or more of the
-      outstanding shares, or (iii) beneficial ownership of such entity.
-
-      "You" (or "Your") shall mean an individual or Legal Entity
-      exercising permissions granted by this License.
-
-      "Source" form shall mean the preferred form for making modifications,
-      including but not limited to software source code, documentation
-      source, and configuration files.
-
-      "Object" form shall mean any form resulting from mechanical
-      transformation or translation of a Source form, including but
-      not limited to compiled object code, generated documentation,
-      and conversions to other media types.
-
-      "Work" shall mean the work of authorship, whether in Source or
-      Object form, made available under the License, as indicated by a
-      copyright notice that is included in or attached to the work
-      (an example is provided in the Appendix below).
-
-      "Derivative Works" shall mean any work, whether in Source or Object
-      form, that is based on (or derived from) the Work and for which the
-      editorial revisions, annotations, elaborations, or other modifications
-      represent, as a whole, an original work of authorship. For the purposes
-      of this License, Derivative Works shall not include works that remain
-      separable from, or merely link (or bind by name) to the interfaces of,
-      the Work and Derivative Works thereof.
-
-      "Contribution" shall mean any work of authorship, including
-      the original version of the Work and any modifications or additions
-      to that Work or Derivative Works thereof, that is intentionally
-      submitted to Licensor for inclusion in the Work by the copyright owner
-      or by an individual or Legal Entity authorized to submit on behalf of
-      the copyright owner. For the purposes of this definition, "submitted"
-      means any form of electronic, verbal, or written communication sent
-      to the Licensor or its representatives, including but not limited to
-      communication on electronic mailing lists, source code control systems,
-      and issue tracking systems that are managed by, or on behalf of, the
-      Licensor for the purpose of discussing and improving the Work, but
-      excluding communication that is conspicuously marked or otherwise
-      designated in writing by the copyright owner as "Not a Contribution."
-
-      "Contributor" shall mean Licensor and any individual or Legal Entity
-      on behalf of whom a Contribution has been received by Licensor and
-      subsequently incorporated within the Work.
-
-   2. Grant of Copyright License. Subject to the terms and conditions of
-      this License, each Contributor hereby grants to You a perpetual,
-      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
-      copyright license to reproduce, prepare Derivative Works of,
-      publicly display, publicly perform, sublicense, and distribute the
-      Work and such Derivative Works in Source or Object form.
-
-   3. Grant of Patent License. Subject to the terms and conditions of
-      this License, each Contributor hereby grants to You a perpetual,
-      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
-      (except as stated in this section) patent license to make, have made,
-      use, offer to sell, sell, import, and otherwise transfer the Work,
-      where such license applies only to those patent claims licensable
-      by such Contributor that are necessarily infringed by their
-      Contribution(s) alone or by combination of their Contribution(s)
-      with the Work to which such Contribution(s) was submitted. If You
-      institute patent litigation against any entity (including a
-      cross-claim or counterclaim in a lawsuit) alleging that the Work
-      or a Contribution incorporated within the Work constitutes direct
-      or contributory patent infringement, then any patent licenses
-      granted to You under this License for that Work shall terminate
-      as of the date such litigation is filed.
-
-   4. Redistribution. You may reproduce and distribute copies of the
-      Work or Derivative Works thereof in any medium, with or without
-      modifications, and in Source or Object form, provided that You
-      meet the following conditions:
-
-      (a) You must give any other recipients of the Work or
-          Derivative Works a copy of this License; and
-
-      (b) You must cause any modified files to carry prominent notices
-          stating that You changed the files; and
-
-      (c) You must retain, in the Source form of any Derivative Works
-          that You distribute, all copyright, patent, trademark, and
-          attribution notices from the Source form of the Work,
-          excluding those notices that do not pertain to any part of
-          the Derivative Works; and
-
-      (d) If the Work includes a "NOTICE" text file as part of its
-          distribution, then any Derivative Works that You distribute must
-          include a readable copy of the attribution notices contained
-          within such NOTICE file, excluding those notices that do not
-          pertain to any part of the Derivative Works, in at least one
-          of the following places: within a NOTICE text file distributed
-          as part of the Derivative Works; within the Source form or
-          documentation, if provided along with the Derivative Works; or,
-          within a display generated by the Derivative Works, if and
-          wherever such third-party notices normally appear. The contents
-          of the NOTICE file are for informational purposes only and
-          do not modify the License. You may add Your own attribution
-          notices within Derivative Works that You distribute, alongside
-          or as an addendum to the NOTICE text from the Work, provided
-          that such additional attribution notices cannot be construed
-          as modifying the License.
-
-      You may add Your own copyright statement to Your modifications and
-      may provide additional or different license terms and conditions
-      for use, reproduction, or distribution of Your modifications, or
-      for any such Derivative Works as a whole, provided Your use,
-      reproduction, and distribution of the Work otherwise complies with
-      the conditions stated in this License.
-
-   5. Submission of Contributions. Unless You explicitly state otherwise,
-      any Contribution intentionally submitted for inclusion in the Work
-      by You to the Licensor shall be under the terms and conditions of
-      this License, without any additional terms or conditions.
-      Notwithstanding the above, nothing herein shall supersede or modify
-      the terms of any separate license agreement you may have executed
-      with Licensor regarding such Contributions.
-
-   6. Trademarks. This License does not grant permission to use the trade
-      names, trademarks, service marks, or product names of the Licensor,
-      except as required for reasonable and customary use in describing the
-      origin of the Work and reproducing the content of the NOTICE file.
-
-   7. Disclaimer of Warranty. Unless required by applicable law or
-      agreed to in writing, Licensor provides the Work (and each
-      Contributor provides its Contributions) on an "AS IS" BASIS,
-      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
-      implied, including, without limitation, any warranties or conditions
-      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
-      PARTICULAR PURPOSE. You are solely responsible for determining the
-      appropriateness of using or redistributing the Work and assume any
-      risks associated with Your exercise of permissions under this License.
-
-   8. Limitation of Liability. In no event and under no legal theory,
-      whether in tort (including negligence), contract, or otherwise,
-      unless required by applicable law (such as deliberate and grossly
-      negligent acts) or agreed to in writing, shall any Contributor be
-      liable to You for damages, including any direct, indirect, special,
-      incidental, or consequential damages of any character arising as a
-      result of this License or out of the use or inability to use the
-      Work (including but not limited to damages for loss of goodwill,
-      work stoppage, computer failure or malfunction, or any and all
-      other commercial damages or losses), even if such Contributor
-      has been advised of the possibility of such damages.
-
-   9. Accepting Warranty or Additional Liability. While redistributing
-      the Work or Derivative Works thereof, You may choose to offer,
-      and charge a fee for, acceptance of support, warranty, indemnity,
-      or other liability obligations and/or rights consistent with this
-      License. However, in accepting such obligations, You may act only
-      on Your own behalf and on Your sole responsibility, not on behalf
-      of any other Contributor, and only if You agree to indemnify,
-      defend, and hold each Contributor harmless for any liability
-      incurred by, or claims asserted against, such Contributor by reason
-      of your accepting any such warranty or additional liability.
-
-   END OF TERMS AND CONDITIONS
-
-   APPENDIX: How to apply the Apache License to your work.
-
-      To apply the Apache License to your work, attach the following
-      boilerplate notice, with the fields enclosed by brackets "[]"
-      replaced with your own identifying information. (Don't include
-      the brackets!)  The text should be enclosed in the appropriate
-      comment syntax for the file format. We also recommend that a
-      file or class name and description of purpose be included on the
-      same "printed page" as the copyright notice for easier
-      identification within third-party archives.
-
-   Copyright [yyyy] [name of copyright owner]
-
-   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.
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/package.xml b/ros2_ws/src/simple_robot_inverse_kinematik/package.xml
deleted file mode 100644
index da002a7..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/package.xml
+++ /dev/null
@@ -1,41 +0,0 @@
-<?xml version="1.0"?>
-<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
-<package format="3">
-  <name>simple_robot_inverse_kinematik</name>
-  <version>0.0.0</version>
-  <description>TODO: Package description</description>
-  <maintainer email="uquzq@student.kit.edu">ventsi</maintainer>
-  <license>Apache-2.0</license>
-
-  <test_depend>ament_copyright</test_depend>
-  <test_depend>ament_flake8</test_depend>
-  <test_depend>ament_pep257</test_depend>
-  <test_depend>python3-pytest</test_depend>
-
-
-  <depend>rclpy</depend>
-  <depend>robot_state_publisher</depend>
-  <depend>rviz2</depend>
-  <depend>joint_state_publisher_gui</depend>
-
-  <depend>builtin_interfaces</depend>
-  <depend>geometry_msgs</depend>
-  <depend>kdl_parser</depend>
-  <depend>orocos_kdl_vendor</depend>
-  <depend>rcl_interfaces</depend>
-  <depend>rclcpp</depend>
-  <depend>rclcpp_components</depend>
-  <depend>sensor_msgs</depend>
-  <depend>std_msgs</depend>
-  <depend>tf2_ros</depend>
-  <depend>urdf</depend>
-
-  <test_depend>ament_copyright</test_depend>
-  <test_depend>ament_flake8</test_depend>
-  <test_depend>ament_pep257</test_depend>
-  <test_depend>python3-pytest</test_depend>
-
-  <export>
-    <build_type>ament_python</build_type>
-  </export>
-</package>
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/resource/simple_robot_inverse_kinematik b/ros2_ws/src/simple_robot_inverse_kinematik/resource/simple_robot_inverse_kinematik
deleted file mode 100644
index e69de29..0000000
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/setup.cfg b/ros2_ws/src/simple_robot_inverse_kinematik/setup.cfg
deleted file mode 100644
index 1682a5a..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[develop]
-script_dir=$base/lib/simple_robot_inverse_kinematik
-[install]
-install_scripts=$base/lib/simple_robot_inverse_kinematik
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/setup.py b/ros2_ws/src/simple_robot_inverse_kinematik/setup.py
deleted file mode 100644
index ae80ba4..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/setup.py
+++ /dev/null
@@ -1,26 +0,0 @@
-from setuptools import find_packages, setup
-
-package_name = 'simple_robot_inverse_kinematik'
-
-setup(
-    name=package_name,
-    version='0.0.0',
-    packages=find_packages(exclude=['test']),
-    data_files=[
-        ('share/ament_index/resource_index/packages',
-            ['resource/' + package_name]),
-        ('share/' + package_name, ['package.xml']),
-    ],
-    install_requires=['setuptools'],
-    zip_safe=True,
-    maintainer='ventsi',
-    maintainer_email='uquzq@student.kit.edu',
-    description='TODO: Package description',
-    license='Apache-2.0',
-    tests_require=['pytest'],
-    entry_points={
-        'console_scripts': [
-            'simple_robot_inverse_kinematik = simple_robot_inverse_kinematik.inverse_kinematik:main',
-        ],
-    },
-)
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/simple_robot_inverse_kinematik/__init__.py b/ros2_ws/src/simple_robot_inverse_kinematik/simple_robot_inverse_kinematik/__init__.py
deleted file mode 100644
index e69de29..0000000
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/simple_robot_inverse_kinematik/inverse_kinematik.py b/ros2_ws/src/simple_robot_inverse_kinematik/simple_robot_inverse_kinematik/inverse_kinematik.py
deleted file mode 100644
index f459080..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/simple_robot_inverse_kinematik/inverse_kinematik.py
+++ /dev/null
@@ -1,75 +0,0 @@
-import os
-
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Pose
-from sensor_msgs.msg import JointState
-from modern_robotics import IKinBody, RpToTrans, FKinBody, IKinSpace
-import numpy as np
-from ament_index_python.packages import get_package_share_directory
-from mr_urdf_loader import loadURDF
-from scipy.spatial.transform import Rotation
-from rclpy.clock import Clock
-
-class InverseKinematicsSimpleRobot(Node):
-    def __init__(self):
-        super().__init__('inverse_kinematics_simple_robot')
-        self.subscription = self.create_subscription(
-            Pose,
-            '/simple_robot/target_pose',
-            self.pose_callback,
-            10)
-        self.publisher = self.create_publisher(JointState, '/joint_states', 10)
-
-        urdf_file_path = os.path.join(
-            get_package_share_directory('simple_robot_1dof'), 'urdf', 'simple_robot.urdf')
-        self.get_logger().info(f'Loading URDF from: {urdf_file_path}')
-        self.simple_robot = loadURDF(urdf_file_path)
-
-        self.M = self.simple_robot["M"]
-        self.Slist = self.simple_robot["Slist"]
-        self.Mlist = self.simple_robot["Mlist"]
-        self.Glist = self.simple_robot["Glist"]
-        self.Blist = self.simple_robot["Blist"]
-
-        
-        self.joint_names = [f'joint{i+1}' for i in range(len(self.Slist[0]))]
-
-        self.joint_angles = np.zeros(len(self.Slist[0]))
-        
-        T = FKinBody(self.M, self.Blist, self.joint_angles)
-        rotation_matrix = T[:3, :3]
-        quat = Rotation.from_matrix(rotation_matrix).as_quat()
-        position = T[:3, 3]
-        self.get_logger().info('T: "%s":' %T)
-
-    def pose_callback(self, pose: Pose):
-        quat = [pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w]
-        r = Rotation.from_quat(quat)
-        rotation_matrix = r.as_matrix()
-        T_sd = RpToTrans(rotation_matrix, np.array([pose.position.x, pose.position.y, pose.position.z]))
-        eomg = 1e-4  # Fehlergrenze für Winkel
-        ev = 1e-4  # Fehlergrenze für Translation
-
-        joint_angles, success = IKinBody(self.Blist, self.M, T_sd, self.joint_angles, eomg, ev)       
-
-        if success:
-            joint_state_msg = JointState()
-            joint_state_msg.header.stamp = Clock().now().to_msg()
-            joint_state_msg.name = self.joint_names
-            joint_state_msg.position = joint_angles.tolist()
-
-            self.publisher.publish(joint_state_msg)
-        else:
-            self.get_logger().error("Inverse Kinematics failed to find a solution.")
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = InverseKinematicsSimpleRobot()
-    rclpy.spin(node)
-    node.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
\ No newline at end of file
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/test/test_copyright.py b/ros2_ws/src/simple_robot_inverse_kinematik/test/test_copyright.py
deleted file mode 100644
index 97a3919..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/test/test_copyright.py
+++ /dev/null
@@ -1,25 +0,0 @@
-# Copyright 2015 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.
-
-from ament_copyright.main import main
-import pytest
-
-
-# Remove the `skip` decorator once the source file(s) have a copyright header
-@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
-@pytest.mark.copyright
-@pytest.mark.linter
-def test_copyright():
-    rc = main(argv=['.', 'test'])
-    assert rc == 0, 'Found errors'
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/test/test_flake8.py b/ros2_ws/src/simple_robot_inverse_kinematik/test/test_flake8.py
deleted file mode 100644
index 27ee107..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/test/test_flake8.py
+++ /dev/null
@@ -1,25 +0,0 @@
-# Copyright 2017 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.
-
-from ament_flake8.main import main_with_errors
-import pytest
-
-
-@pytest.mark.flake8
-@pytest.mark.linter
-def test_flake8():
-    rc, errors = main_with_errors(argv=[])
-    assert rc == 0, \
-        'Found %d code style errors / warnings:\n' % len(errors) + \
-        '\n'.join(errors)
diff --git a/ros2_ws/src/simple_robot_inverse_kinematik/test/test_pep257.py b/ros2_ws/src/simple_robot_inverse_kinematik/test/test_pep257.py
deleted file mode 100644
index b234a38..0000000
--- a/ros2_ws/src/simple_robot_inverse_kinematik/test/test_pep257.py
+++ /dev/null
@@ -1,23 +0,0 @@
-# Copyright 2015 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.
-
-from ament_pep257.main import main
-import pytest
-
-
-@pytest.mark.linter
-@pytest.mark.pep257
-def test_pep257():
-    rc = main(argv=['.', 'test'])
-    assert rc == 0, 'Found code style errors / warnings'
-- 
GitLab