diff --git a/launch/test_attacher.py b/launch/test_attacher.py index d473209..0fd9fc9 100644 --- a/launch/test_attacher.py +++ b/launch/test_attacher.py @@ -23,7 +23,7 @@ from launch.actions import OpaqueFunction -def launch_setup(): +def launch_setup(context, *args, **kwargs): # Start Gazebo with an empty world file gazebo_launch = os.path.join( get_package_share_directory('gazebo_ros'), 'launch/gazebo.launch.py') diff --git a/package.xml b/package.xml index ac419db..b6fb112 100644 --- a/package.xml +++ b/package.xml @@ -17,7 +17,7 @@ gazebo std_msgs - python-transforms3d-pip + transforms3d rclcpp gazebo_ros diff --git a/scripts/attach.py b/scripts/attach.py index 879bb87..d89f686 100755 --- a/scripts/attach.py +++ b/scripts/attach.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + # Copyright (c) 2023, SENAI Cimatec # # Licensed under the Apache License, Version 2.0 (the "License"); @@ -12,7 +14,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -# !/usr/bin/env python3 import sys import rclpy diff --git a/scripts/demo.py b/scripts/demo.py index 96e0971..6a9ccf7 100755 --- a/scripts/demo.py +++ b/scripts/demo.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + # Copyright (c) 2023, SENAI Cimatec # # Licensed under the Apache License, Version 2.0 (the "License"); @@ -12,7 +14,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -# !/usr/bin/env python3 import sys from copy import deepcopy diff --git a/scripts/demo_multiple.py b/scripts/demo_multiple.py index 83ce658..b463d41 100755 --- a/scripts/demo_multiple.py +++ b/scripts/demo_multiple.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + # Copyright (c) 2023, SENAI Cimatec # # Licensed under the Apache License, Version 2.0 (the "License"); @@ -12,7 +14,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -# !/usr/bin/env python3 + from copy import deepcopy import sys import rclpy diff --git a/scripts/detach.py b/scripts/detach.py index abcbe77..a68ee20 100755 --- a/scripts/detach.py +++ b/scripts/detach.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + # Copyright (c) 2023, SENAI Cimatec # # Licensed under the Apache License, Version 2.0 (the "License"); @@ -12,7 +14,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -# !/usr/bin/env python3 import sys import rclpy diff --git a/scripts/spawn_models.py b/scripts/spawn_models.py index 1f4a56b..e18ebbb 100755 --- a/scripts/spawn_models.py +++ b/scripts/spawn_models.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + # Copyright (c) 2023, SENAI Cimatec # # Licensed under the Apache License, Version 2.0 (the "License"); @@ -12,10 +14,8 @@ # See the License for the specific language governing permissions and # limitations under the License. -# !/usr/bin/env python3 - -from copy import deepcopy import sys +from copy import deepcopy import rclpy from gazebo_msgs.srv import SpawnEntity from transforms3d.euler import euler2quat