Skip to content

Commit

Permalink
Fix issues in code style and transform3d dependency
Browse files Browse the repository at this point in the history
  • Loading branch information
claudiaelizabete committed Jan 18, 2024
1 parent 72e002a commit f4cc6d9
Show file tree
Hide file tree
Showing 7 changed files with 14 additions and 9 deletions.
2 changes: 1 addition & 1 deletion launch/test_attacher.py
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<build_depend>gazebo</build_depend>
<build_depend>std_msgs</build_depend>

<build_depend>python-transforms3d-pip</build_depend>
<build_depend>transforms3d</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>gazebo_ros</exec_depend>
Expand Down
3 changes: 2 additions & 1 deletion scripts/attach.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

# Copyright (c) 2023, SENAI Cimatec
#
# Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -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
Expand Down
3 changes: 2 additions & 1 deletion scripts/demo.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

# Copyright (c) 2023, SENAI Cimatec
#
# Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -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
Expand Down
4 changes: 3 additions & 1 deletion scripts/demo_multiple.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

# Copyright (c) 2023, SENAI Cimatec
#
# Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -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
Expand Down
3 changes: 2 additions & 1 deletion scripts/detach.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

# Copyright (c) 2023, SENAI Cimatec
#
# Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -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
Expand Down
6 changes: 3 additions & 3 deletions scripts/spawn_models.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#!/usr/bin/env python3

# Copyright (c) 2023, SENAI Cimatec
#
# Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -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
Expand Down

0 comments on commit f4cc6d9

Please sign in to comment.