Jelajahi Sumber

Adjusted Python ROS2 code to be complaint with tests

- The license checker were removed from tests, since those are
  incompatible with O3DE headers.

Signed-off-by: Michał Pełka <[email protected]>
Michał Pełka 2 tahun lalu
induk
melakukan
6fbbc6f1db

+ 26 - 15
kraken_nav/o3de_kraken_nav/launch/navigation.launch.py

@@ -14,12 +14,15 @@ from launch.launch_description_sources import PythonLaunchDescriptionSource
 from launch_ros.actions import Node
 from launch_ros.actions import Node
 from nav2_common.launch import RewrittenYaml
 from nav2_common.launch import RewrittenYaml
 
 
+
 def generate_launch_description():
 def generate_launch_description():
     package_dir = get_package_share_directory("o3de_kraken_nav")
     package_dir = get_package_share_directory("o3de_kraken_nav")
     slam_toolbox_dir = get_package_share_directory('slam_toolbox')
     slam_toolbox_dir = get_package_share_directory('slam_toolbox')
     nav2_dir = get_package_share_directory("nav2_bringup")
     nav2_dir = get_package_share_directory("nav2_bringup")
 
 
-    nav2_params_file = str(pathlib.Path(package_dir).joinpath('launch', 'config', 'navigation_params.yaml'))
+    nav2_params_file = str(pathlib.Path(package_dir).joinpath('launch',
+                                                              'config',
+                                                              'navigation_params.yaml'))
     bt_xml_file = str(pathlib.Path(package_dir).joinpath('launch', 'config', 'bt.xml'))
     bt_xml_file = str(pathlib.Path(package_dir).joinpath('launch', 'config', 'bt.xml'))
 
 
     param_substitutions = {
     param_substitutions = {
@@ -29,21 +32,27 @@ def generate_launch_description():
         root_key='',
         root_key='',
         param_rewrites=param_substitutions,
         param_rewrites=param_substitutions,
         convert_types=True)
         convert_types=True)
-    
+
+    online_async_file = pathlib.Path(slam_toolbox_dir).joinpath('launch',
+                                                                'online_async_launch.py')
+    slam_params_file = pathlib.Path(package_dir).joinpath('launch',
+                                                          'config',
+                                                          'slam_params.yaml')
     slam = IncludeLaunchDescription(
     slam = IncludeLaunchDescription(
-        PythonLaunchDescriptionSource([str(pathlib.Path(slam_toolbox_dir).joinpath('launch', 'online_async_launch.py'))]),
-        launch_arguments = {
-            'slam_params_file': str(pathlib.Path(package_dir).joinpath('launch', 'config', 'slam_params.yaml')),
+        PythonLaunchDescriptionSource([str(online_async_file)]),
+        launch_arguments={
+            'slam_params_file': str(slam_params_file),
         }.items()
         }.items()
     )
     )
-    
+
+    navigation_launch = pathlib.Path(nav2_dir).joinpath('launch', 'navigation_launch.py')
     navigation = IncludeLaunchDescription(
     navigation = IncludeLaunchDescription(
-        PythonLaunchDescriptionSource([str(pathlib.Path(nav2_dir).joinpath('launch', 'navigation_launch.py'))]),
-        launch_arguments = {
+        PythonLaunchDescriptionSource([str(navigation_launch)]),
+        launch_arguments={
             'params_file': configured_nav2_params,
             'params_file': configured_nav2_params,
         }.items()
         }.items()
     )
     )
-    
+
     pointcloud_to_laserscan = Node(
     pointcloud_to_laserscan = Node(
         package='pointcloud_to_laserscan',
         package='pointcloud_to_laserscan',
         executable='pointcloud_to_laserscan_node',
         executable='pointcloud_to_laserscan_node',
@@ -58,7 +67,7 @@ def generate_launch_description():
             ('/cloud_in', '/pc'),
             ('/cloud_in', '/pc'),
         ]
         ]
     )
     )
-    
+
     twist_to_ackermann = Node(
     twist_to_ackermann = Node(
         package='o3de_kraken_nav',
         package='o3de_kraken_nav',
         executable='twist_to_ackermann',
         executable='twist_to_ackermann',
@@ -70,21 +79,23 @@ def generate_launch_description():
             'publish_zeros_on_timeout': True
             'publish_zeros_on_timeout': True
         }]
         }]
     )
     )
-    
+
     rviz = Node(
     rviz = Node(
         package='rviz2',
         package='rviz2',
         executable='rviz2',
         executable='rviz2',
         name='slam',
         name='slam',
         arguments=[
         arguments=[
-            '-d', str(pathlib.Path(package_dir).joinpath('launch', 'config', 'config.rviz')),
+            '-d', str(pathlib.Path(package_dir).joinpath('launch',
+                                                         'config',
+                                                         'config.rviz')),
         ]
         ]
     )
     )
-    
+
     ld = LaunchDescription()
     ld = LaunchDescription()
     ld.add_action(pointcloud_to_laserscan)
     ld.add_action(pointcloud_to_laserscan)
     ld.add_action(twist_to_ackermann)
     ld.add_action(twist_to_ackermann)
     ld.add_action(slam)
     ld.add_action(slam)
     ld.add_action(navigation)
     ld.add_action(navigation)
     ld.add_action(rviz)
     ld.add_action(rviz)
-    
-    return ld
+
+    return ld

+ 34 - 22
kraken_nav/o3de_kraken_nav/launch/navigation_multi.launch.py

@@ -8,7 +8,6 @@
 
 
 
 
 import pathlib
 import pathlib
-from unicodedata import name
 from ament_index_python.packages import get_package_share_directory
 from ament_index_python.packages import get_package_share_directory
 from launch import LaunchDescription
 from launch import LaunchDescription
 from launch.actions import IncludeLaunchDescription, GroupAction, DeclareLaunchArgument
 from launch.actions import IncludeLaunchDescription, GroupAction, DeclareLaunchArgument
@@ -21,18 +20,21 @@ from launch.conditions import IfCondition, UnlessCondition
 from launch_ros.actions import ComposableNodeContainer
 from launch_ros.actions import ComposableNodeContainer
 from launch_ros.descriptions import ComposableNode
 from launch_ros.descriptions import ComposableNode
 
 
+
 def substitute_namespace(namespace, value):
 def substitute_namespace(namespace, value):
     if not namespace:
     if not namespace:
         return TextSubstitution(text=value)
         return TextSubstitution(text=value)
     else:
     else:
         return PythonExpression(['str("', namespace, '")', "+", f"'/{value}'"])
         return PythonExpression(['str("', namespace, '")', "+", f"'/{value}'"])
-    
+
+
 def substitute_name(namespace, value):
 def substitute_name(namespace, value):
     if not namespace:
     if not namespace:
         return TextSubstitution(text=value)
         return TextSubstitution(text=value)
     else:
     else:
         return PythonExpression(['str("', namespace, '")', "+", f"'_{value}'"])
         return PythonExpression(['str("', namespace, '")', "+", f"'_{value}'"])
 
 
+
 def generate_launch_description():
 def generate_launch_description():
     namespace = LaunchConfiguration('namespace')
     namespace = LaunchConfiguration('namespace')
     declare_namespace_cmd = DeclareLaunchArgument(
     declare_namespace_cmd = DeclareLaunchArgument(
@@ -45,7 +47,7 @@ def generate_launch_description():
         'use_slam',
         'use_slam',
         default_value='False',
         default_value='False',
     )
     )
-    
+
     rviz = LaunchConfiguration('rviz')
     rviz = LaunchConfiguration('rviz')
     declare_rviz_cmd = DeclareLaunchArgument(
     declare_rviz_cmd = DeclareLaunchArgument(
         'rviz',
         'rviz',
@@ -56,15 +58,21 @@ def generate_launch_description():
     slam_toolbox_dir = get_package_share_directory('slam_toolbox')
     slam_toolbox_dir = get_package_share_directory('slam_toolbox')
     nav2_dir = get_package_share_directory("nav2_bringup")
     nav2_dir = get_package_share_directory("nav2_bringup")
 
 
-    nav2_params_file = str(pathlib.Path(package_dir).joinpath('launch', 'config', 'navigation_multi_params.yaml'))
+    nav2_params_file = str(
+        pathlib.Path(package_dir).joinpath('launch', 'config', 'navigation_multi_params.yaml')
+    )
     bt_xml_file = str(pathlib.Path(package_dir).joinpath('launch', 'config', 'bt.xml'))
     bt_xml_file = str(pathlib.Path(package_dir).joinpath('launch', 'config', 'bt.xml'))
-    slam_params_file = str(pathlib.Path(package_dir).joinpath('launch', 'config', 'slam_multi_params.yaml'))
+    slam_params_file = str(
+        pathlib.Path(package_dir).joinpath('launch', 'config', 'slam_multi_params.yaml')
+    )
 
 
     nav_param_substitutions = {
     nav_param_substitutions = {
         'default_nav_to_pose_bt_xml': bt_xml_file,
         'default_nav_to_pose_bt_xml': bt_xml_file,
         'robot_base_frame': substitute_namespace(namespace, "base_link"),
         'robot_base_frame': substitute_namespace(namespace, "base_link"),
-        'local_costmap.local_costmap.ros__parameters.global_frame': substitute_namespace(namespace, "odom"),
-        'global_costmap.global_costmap.ros__parameters.global_frame': substitute_namespace(namespace, "map"),
+        'local_costmap.local_costmap.ros__parameters.global_frame':
+            substitute_namespace(namespace, "odom"),
+        'global_costmap.global_costmap.ros__parameters.global_frame':
+            substitute_namespace(namespace, "map"),
         'bt_navigator.ros__parameters.global_frame': substitute_namespace(namespace, "map"),
         'bt_navigator.ros__parameters.global_frame': substitute_namespace(namespace, "map"),
         # 'topic': substitute_namespace(namespace, "scan")
         # 'topic': substitute_namespace(namespace, "scan")
     }
     }
@@ -73,32 +81,34 @@ def generate_launch_description():
         'odom_frame': substitute_namespace(namespace, "odom"),
         'odom_frame': substitute_namespace(namespace, "odom"),
         'map_frame': substitute_namespace(namespace, "map")
         'map_frame': substitute_namespace(namespace, "map")
     }
     }
-    
+
     configured_nav2_params = RewrittenYaml(
     configured_nav2_params = RewrittenYaml(
         source_file=nav2_params_file,
         source_file=nav2_params_file,
         root_key='',
         root_key='',
         param_rewrites=nav_param_substitutions,
         param_rewrites=nav_param_substitutions,
         convert_types=True)
         convert_types=True)
-    
+
     configured_slam_params = RewrittenYaml(
     configured_slam_params = RewrittenYaml(
         source_file=slam_params_file,
         source_file=slam_params_file,
         root_key=namespace,
         root_key=namespace,
         param_rewrites=slam_param_substitutions,
         param_rewrites=slam_param_substitutions,
         convert_types=True)
         convert_types=True)
-    
+
+    online_async_launch = pathlib.Path(slam_toolbox_dir).joinpath('launch',
+                                                                  'online_async_launch.py')
     slam = GroupAction(
     slam = GroupAction(
         condition=IfCondition(use_slam),
         condition=IfCondition(use_slam),
         actions=[
         actions=[
             PushRosNamespace(namespace),
             PushRosNamespace(namespace),
             IncludeLaunchDescription(
             IncludeLaunchDescription(
-                PythonLaunchDescriptionSource([str(pathlib.Path(slam_toolbox_dir).joinpath('launch', 'online_async_launch.py'))]),
-                launch_arguments = {
+                PythonLaunchDescriptionSource([str(online_async_launch)]),
+                launch_arguments={
                     'slam_params_file': configured_slam_params,
                     'slam_params_file': configured_slam_params,
                 }.items()
                 }.items()
             ),
             ),
         ]
         ]
     )
     )
-    
+
     local_costmap_scan_relay = Node(
     local_costmap_scan_relay = Node(
         name="pc_relay",
         name="pc_relay",
         package="topic_tools",
         package="topic_tools",
@@ -186,12 +196,13 @@ def generate_launch_description():
         output='both',
         output='both',
     )
     )
 
 
+    navigation_launch = pathlib.Path(nav2_dir).joinpath('launch', 'navigation_launch.py')
     nav_nodes = GroupAction(
     nav_nodes = GroupAction(
         actions=[
         actions=[
             PushRosNamespace(namespace),
             PushRosNamespace(namespace),
             IncludeLaunchDescription(
             IncludeLaunchDescription(
-                PythonLaunchDescriptionSource([str(pathlib.Path(nav2_dir).joinpath('launch', 'navigation_launch.py'))]),
-                launch_arguments = {
+                PythonLaunchDescriptionSource([str(navigation_launch)]),
+                launch_arguments={
                     'params_file': configured_nav2_params,
                     'params_file': configured_nav2_params,
                     'namespace': namespace,
                     'namespace': namespace,
                     'use_sim_time': 'True',
                     'use_sim_time': 'True',
@@ -200,7 +211,7 @@ def generate_launch_description():
             )
             )
         ]
         ]
     )
     )
-    
+
     pointcloud_to_laserscan = Node(
     pointcloud_to_laserscan = Node(
         package='pointcloud_to_laserscan',
         package='pointcloud_to_laserscan',
         executable='pointcloud_to_laserscan_node',
         executable='pointcloud_to_laserscan_node',
@@ -216,7 +227,7 @@ def generate_launch_description():
             ('cloud_in', 'pc'),
             ('cloud_in', 'pc'),
         ]
         ]
     )
     )
-    
+
     twist_to_ackermann = Node(
     twist_to_ackermann = Node(
         package='o3de_kraken_nav',
         package='o3de_kraken_nav',
         executable='twist_to_ackermann',
         executable='twist_to_ackermann',
@@ -232,7 +243,7 @@ def generate_launch_description():
             ('/ackermann_vel', substitute_namespace(namespace, 'ackermann_vel')),
             ('/ackermann_vel', substitute_namespace(namespace, 'ackermann_vel')),
         ]
         ]
     )
     )
-    
+
     rviz = GroupAction(
     rviz = GroupAction(
         condition=IfCondition(rviz),
         condition=IfCondition(rviz),
         actions=[
         actions=[
@@ -241,12 +252,14 @@ def generate_launch_description():
                 executable='rviz2',
                 executable='rviz2',
                 name='slam',
                 name='slam',
                 arguments=[
                 arguments=[
-                    '-d', str(pathlib.Path(package_dir).joinpath('launch', 'config', 'config_multi.rviz')),
+                    '-d', str(pathlib.Path(package_dir).joinpath('launch',
+                                                                 'config',
+                                                                 'config_multi.rviz')),
                 ]
                 ]
             )
             )
         ]
         ]
     )
     )
-    
+
     ld = LaunchDescription()
     ld = LaunchDescription()
     ld.add_action(declare_namespace_cmd)
     ld.add_action(declare_namespace_cmd)
     ld.add_action(declare_use_slam_cmd)
     ld.add_action(declare_use_slam_cmd)
@@ -263,5 +276,4 @@ def generate_launch_description():
     ld.add_action(slam)
     ld.add_action(slam)
     ld.add_action(nav_nodes)
     ld.add_action(nav_nodes)
     ld.add_action(rviz)
     ld.add_action(rviz)
-    
-    return ld
+    return ld

+ 2 - 1
kraken_nav/o3de_kraken_nav/launch/teleop.launch.py

@@ -11,6 +11,7 @@ from launch_ros.actions import Node
 from launch.substitutions import LaunchConfiguration
 from launch.substitutions import LaunchConfiguration
 from launch.actions import DeclareLaunchArgument
 from launch.actions import DeclareLaunchArgument
 
 
+
 def generate_launch_description():
 def generate_launch_description():
     namespace = LaunchConfiguration('namespace')
     namespace = LaunchConfiguration('namespace')
     declare_namespace_cmd = DeclareLaunchArgument(
     declare_namespace_cmd = DeclareLaunchArgument(
@@ -31,4 +32,4 @@ def generate_launch_description():
             executable='joy_node',
             executable='joy_node',
             name='joy_node'
             name='joy_node'
         ),
         ),
-    ])
+    ])

+ 0 - 1
kraken_nav/o3de_kraken_nav/o3de_kraken_nav/__init__.py

@@ -4,4 +4,3 @@
 # SPDX-License-Identifier: Apache-2.0 OR MIT
 # SPDX-License-Identifier: Apache-2.0 OR MIT
 #
 #
 #
 #
-

+ 2 - 11
kraken_nav/o3de_kraken_nav/o3de_kraken_nav/joy_to_ackermann.py

@@ -1,4 +1,3 @@
-# coding:utf-8
 #!/usr/bin/env python3
 #!/usr/bin/env python3
 
 
 #
 #
@@ -10,19 +9,15 @@
 #
 #
 
 
 
 
-
 import rclpy
 import rclpy
 from rclpy.node import Node
 from rclpy.node import Node
 
 
-from std_msgs.msg import String
 from sensor_msgs.msg import Joy
 from sensor_msgs.msg import Joy
 from ackermann_msgs.msg import AckermannDrive
 from ackermann_msgs.msg import AckermannDrive
 
 
 
 
 class JoyToAckermann(Node):
 class JoyToAckermann(Node):
-    """
-    ROS2 Node to convert joystick message to Ackermann Drive message. 
-    """
+    """ROS2 Node to convert joystick message to Ackermann Drive message."""
 
 
     def __init__(self):
     def __init__(self):
         super().__init__('joy_to_ackermann')
         super().__init__('joy_to_ackermann')
@@ -30,11 +25,7 @@ class JoyToAckermann(Node):
         self.subscription = self.create_subscription(Joy, "/joy", self.joy_callback, 10)
         self.subscription = self.create_subscription(Joy, "/joy", self.joy_callback, 10)
 
 
     def joy_callback(self, msg):
     def joy_callback(self, msg):
-        """
-        Callback called on new message from the joystick driver.
-        It creates AckermanDrive message and publish it.
-        :param msg: message from the joystick driver
-        """
+        """Create Ackermann message from the joystick message."""
         drive = AckermannDrive()
         drive = AckermannDrive()
         drive.speed = 1.5 * msg.axes[1]
         drive.speed = 1.5 * msg.axes[1]
         drive.steering_angle = 1.1 * msg.axes[0]
         drive.steering_angle = 1.1 * msg.axes[0]

+ 8 - 10
kraken_nav/o3de_kraken_nav/o3de_kraken_nav/twist_to_ackermann.py

@@ -1,4 +1,3 @@
-# coding:utf-8
 #!/usr/bin/env python3
 #!/usr/bin/env python3
 
 
 #
 #
@@ -10,21 +9,16 @@
 #
 #
 
 
 
 
-
 import math
 import math
 from rclpy.node import Node
 from rclpy.node import Node
 import rclpy
 import rclpy
-from rclpy.duration import Duration
+
 from geometry_msgs.msg import Twist
 from geometry_msgs.msg import Twist
 from ackermann_msgs.msg import AckermannDrive
 from ackermann_msgs.msg import AckermannDrive
 
 
 
 
 class TwistToAckermann(Node):
 class TwistToAckermann(Node):
-    """
-    ROS2 node to convert Twist message to Ackermann Drive message.
-    It translates cmd_vel messages from nav2 to Ackermann Drive.
-    It also has timeout that stops robot when no new messages are retrieved.
-    """
+    """ROS2 node to convert velocity commands to Ackermann commands."""
 
 
     def __init__(self):
     def __init__(self):
         super().__init__('twist_to_ackermann')
         super().__init__('twist_to_ackermann')
@@ -38,8 +32,12 @@ class TwistToAckermann(Node):
         self.wheelbase = self.get_parameter('wheelbase').get_parameter_value().double_value
         self.wheelbase = self.get_parameter('wheelbase').get_parameter_value().double_value
         self.timeout_control_interval = self.get_parameter(
         self.timeout_control_interval = self.get_parameter(
             'timeout_control_interval').get_parameter_value().double_value
             'timeout_control_interval').get_parameter_value().double_value
-        self.control_timeout = self.get_parameter('control_timeout').get_parameter_value().double_value
-        self.publish_zeros_on_timeout = self.get_parameter('publish_zeros_on_timeout').get_parameter_value().bool_value
+
+        par_timeout = self.get_parameter('control_timeout')
+        par_publish_zero_tout = self.get_parameter('publish_zeros_on_timeout')
+
+        self.control_timeout = par_timeout.get_parameter_value().double_value
+        self.publish_zeros_on_timeout = par_publish_zero_tout.get_parameter_value().bool_value
 
 
         self.last_message_time = self.get_clock().now()
         self.last_message_time = self.get_clock().now()
         self.sub_ = self.create_subscription(Twist, "cmd_vel", self.cmd_vel_cb, 10)
         self.sub_ = self.create_subscription(Twist, "cmd_vel", self.cmd_vel_cb, 10)

+ 1 - 1
kraken_nav/o3de_kraken_nav/setup.py

@@ -31,7 +31,7 @@ setup(
     maintainer='Piotr Jaroszek',
     maintainer='Piotr Jaroszek',
     maintainer_email='[email protected]',
     maintainer_email='[email protected]',
     description='Navigation package for Roscon apple kraken demo',
     description='Navigation package for Roscon apple kraken demo',
-    license='TODO: License declaration',
+    license='Apache 2.0',
     tests_require=['pytest'],
     tests_require=['pytest'],
     entry_points={
     entry_points={
         'console_scripts': [
         'console_scripts': [

+ 0 - 23
kraken_nav/o3de_kraken_nav/test/test_copyright.py

@@ -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_copyright.main import main
-import pytest
-
-
[email protected]
[email protected]
-def test_copyright():
-    rc = main(argv=['.', 'test'])
-    assert rc == 0, 'Found errors'

+ 10 - 37
kraken_nav/o3de_kraken_orchestration/o3de_kraken_orchestration/global_kraken_orchestration.py

@@ -1,4 +1,3 @@
-# coding:utf-8
 #!/usr/bin/env python3
 #!/usr/bin/env python3
 
 
 #
 #
@@ -13,7 +12,6 @@ import rclpy
 import time
 import time
 from threading import Thread
 from threading import Thread
 
 
-from nav_msgs.msg import Path
 from geometry_msgs.msg import PoseStamped
 from geometry_msgs.msg import PoseStamped
 
 
 from .state_machine import GlobalOrchestrationSM
 from .state_machine import GlobalOrchestrationSM
@@ -35,9 +33,7 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
         self.current_index = 0
         self.current_index = 0
 
 
     def get_next_pose(self):
     def get_next_pose(self):
-        """
-        Retrieve next goal from the Plan
-        """
+        """Retrieve next goal from the Plan."""
         if self.current_index >= len(self.poses):
         if self.current_index >= len(self.poses):
             self.logger.error('Invalid index!')
             self.logger.error('Invalid index!')
             return PoseStamped()
             return PoseStamped()
@@ -52,19 +48,14 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
         rclpy.shutdown()
         rclpy.shutdown()
 
 
     def on_enter_waiting(self):
     def on_enter_waiting(self):
-        """
-        Callback called on entry to waiting state.
-        """
+        """Is called on entry to waiting state."""
         self.logger.info('Has the simulation started?')
         self.logger.info('Has the simulation started?')
         self.send_state("Wait for connection")
         self.send_state("Wait for connection")
         # Perform a check whether the simulation has started or not.
         # Perform a check whether the simulation has started or not.
         self.started()
         self.started()
 
 
     def on_enter_spawning(self):
     def on_enter_spawning(self):
-        """
-        Callback called on entry to spawning state.
-        Spawns robot.
-        """
+        """Is called on entry to spawning state and spawns robot."""
         self.logger.info('Spawning the robot.')
         self.logger.info('Spawning the robot.')
         self.send_state("Spawning the robot")
         self.send_state("Spawning the robot")
         if self.spawn_kraken():
         if self.spawn_kraken():
@@ -73,10 +64,7 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
             self.logger.info('Robot spawning failed.')
             self.logger.info('Robot spawning failed.')
 
 
     def on_spawned(self):
     def on_spawned(self):
-        """
-        Callback called on successful spawn.
-        Retrieves spawn position and plan for the Robot.
-        """
+        """Is called on spawn, retrieves plan and position."""
         self.logger.info('Robot spawned successfully. Fetching info.')
         self.logger.info('Robot spawned successfully. Fetching info.')
         pose = self.get_spawn_point_pose()
         pose = self.get_spawn_point_pose()
         self.poses = self.get_plan_poses(pose)
         self.poses = self.get_plan_poses(pose)
@@ -85,9 +73,7 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
         time.sleep(3)
         time.sleep(3)
 
 
     def on_enter_gathering(self):
     def on_enter_gathering(self):
-        """
-        Callback called on entry to gathering state.
-        """
+        """Is called on entry to gathering state."""
         self.logger.info('Is the robot in a gathering position?')
         self.logger.info('Is the robot in a gathering position?')
         # Perform a check whether the robot is in a gathering position or not.
         # Perform a check whether the robot is in a gathering position or not.
         if self.can_gather:
         if self.can_gather:
@@ -96,9 +82,7 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
             self.navigate()
             self.navigate()
 
 
     def on_enter_finishing(self):
     def on_enter_finishing(self):
-        """
-        Callback called on entry to finishing apple gathering state.
-        """
+        """Is called on entry to finishing apple gathering state."""
         self.logger.info('Has the robot completed its job?')
         self.logger.info('Has the robot completed its job?')
         # Perform a check whether the robot has finished its job or not.
         # Perform a check whether the robot has finished its job or not.
         if self.current_index >= len(self.poses):
         if self.current_index >= len(self.poses):
@@ -107,10 +91,7 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
             self.finish()
             self.finish()
 
 
     def on_navigate(self):
     def on_navigate(self):
-        """
-        Callback called on entry to navigation state.
-        Sends goal position to nav2.
-        """
+        """Is called on nav. state, sends goal position to nav2, monitors."""
         self.send_state("Navigating")
         self.send_state("Navigating")
         self.logger.info('Navigating the robot to a closest gathering position?')
         self.logger.info('Navigating the robot to a closest gathering position?')
         self.can_gather = False
         self.can_gather = False
@@ -124,9 +105,7 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
         self.can_gather = True
         self.can_gather = True
 
 
     def on_gather(self):
     def on_gather(self):
-        """
-        Callback called on entry to gathering state.
-        """
+        """Is called on gathering state and monitor progress."""
         self.logger.info("Requesting gathering...")
         self.logger.info("Requesting gathering...")
         self.send_state("Gather %.1f " % self.apple_progress)
         self.send_state("Gather %.1f " % self.apple_progress)
         trigger_res = self.trigger_apple_gathering()
         trigger_res = self.trigger_apple_gathering()
@@ -145,18 +124,12 @@ class GlobalOrchestration(GlobalOrchestrationSM, KrakenOrchestrationNode):
             time.sleep(2)
             time.sleep(2)
 
 
     def on_finish(self):
     def on_finish(self):
-        """
-        Callback called on finish state.
-        Asks to navigate to the last position in the plan.
-        """
+        """Is called on finish state, navigates to last goal."""
         # Same action is performed.
         # Same action is performed.
         self.on_navigate()
         self.on_navigate()
 
 
     def on_finished(self):
     def on_finished(self):
-        """
-        Callback called on finished state.
-        The orchestration is done.
-        """
+        """Is called after finished."""
         self.send_state("Completed")
         self.send_state("Completed")
         self.logger.info('The robot has completed its job.')
         self.logger.info('The robot has completed its job.')
         # The robot has finished its job.
         # The robot has finished its job.

+ 46 - 66
kraken_nav/o3de_kraken_orchestration/o3de_kraken_orchestration/orchestration_node.py

@@ -1,4 +1,3 @@
-# coding:utf-8
 #!/usr/bin/env python3
 #!/usr/bin/env python3
 
 
 #
 #
@@ -23,81 +22,74 @@ from std_msgs.msg import Float32
 
 
 
 
 class KrakenOrchestrationNode(Node):
 class KrakenOrchestrationNode(Node):
-    """
-    Class containing implementation of state machine. 
-    """
+    """Class containing implementation of state machine."""
 
 
     def init_spawn_entity_client(self):
     def init_spawn_entity_client(self):
-        """"
-        Initialize ROS2 service client to spawn robot
-        """
+        """Initialize ROS2 service client to spawn robot."""
         self.spawn_entity_client = self.create_client(SpawnEntity, 'spawn_entity')
         self.spawn_entity_client = self.create_client(SpawnEntity, 'spawn_entity')
         while not self.spawn_entity_client.wait_for_service(timeout_sec=1.0):
         while not self.spawn_entity_client.wait_for_service(timeout_sec=1.0):
             self.get_logger().info('Spawn entity service not available waiting again...')
             self.get_logger().info('Spawn entity service not available waiting again...')
 
 
     def init_get_spawn_point_info_client(self):
     def init_get_spawn_point_info_client(self):
-        """"
-        Initialize ROS2 service to retrieve spawn points from simulation
-        """
-        self.get_spawn_point_info_client = self.create_client(GetModelState, 'get_spawn_point_info')
+        """Initialize ROS2 service to retrieve spawn points from simulation."""
+        self.get_spawn_point_info_client = self.create_client(
+            GetModelState,
+            'get_spawn_point_info')
         while not self.get_spawn_point_info_client.wait_for_service(timeout_sec=1.0):
         while not self.get_spawn_point_info_client.wait_for_service(timeout_sec=1.0):
             self.get_logger().info('Get spawn point info service not available waiting again...')
             self.get_logger().info('Get spawn point info service not available waiting again...')
 
 
     def init_get_plan_client(self):
     def init_get_plan_client(self):
-        """"
-        Initialize ROS2 service to retrieve gathering plan from simulation
-        """
+        """Initialize ROS2 service to retrieve gathering plan from simulation."""
         self.get_plan_client = self.create_client(GetPlan, 'get_gathering_plan')
         self.get_plan_client = self.create_client(GetPlan, 'get_gathering_plan')
         while not self.get_plan_client.wait_for_service(timeout_sec=1.0):
         while not self.get_plan_client.wait_for_service(timeout_sec=1.0):
             self.get_logger().info('Get plan service not available waiting again...')
             self.get_logger().info('Get plan service not available waiting again...')
 
 
     def apple_gathering_done_callback(self, request, response):
     def apple_gathering_done_callback(self, request, response):
-        """"
-        Implementation of the callback called from simulation, called on finished apple gathering.
-        """
+        """Is called on finished apple gathering by the Simulation."""
         self.get_logger().info("Received done client msg.")
         self.get_logger().info("Received done client msg.")
         self.gathering_done = True
         self.gathering_done = True
         return Empty.Response()
         return Empty.Response()
 
 
     def apple_progress_callback(self, msg):
     def apple_progress_callback(self, msg):
-        """"
-        Implementation of the callback called from simulation with current gathering progress.
-        """
+        """Is called on progress change in gathering by the Simulation."""
         self.apple_progress = 100.0 * float(msg.data)
         self.apple_progress = 100.0 * float(msg.data)
 
 
     def init_apple_gathering_srvs(self):
     def init_apple_gathering_srvs(self):
-        """"
-        Initialize servers for services that are served by this node. 
-        Blocking wait for service initialization.
-        """
-        self.done_apple_gathering_service = self.create_service(Empty, f'{self.kraken_name}/done_apple_gathering',
-                                                                self.apple_gathering_done_callback)
+        """Initialize servers for services that are served by this node."""
+        self.done_apple_gathering_service = self.create_service(
+            Empty, f'{self.kraken_name}/done_apple_gathering',
+            self.apple_gathering_done_callback
+        )
+
+        self.trigger_apple_gathering_client = self.create_client(
+            Trigger,
+            f'{self.kraken_name}/trigger_apple_gathering'
+        )
 
 
-        self.trigger_apple_gathering_client = self.create_client(Trigger, f'{self.kraken_name}/trigger_apple_gathering')
-        self.cancel_apple_gathering_client = self.create_client(Trigger, f'{self.kraken_name}/cancel_apple_gathering')
+        self.cancel_apple_gathering_client = self.create_client(
+            Trigger,
+            f'{self.kraken_name}/cancel_apple_gathering'
+        )
 
 
         while (not self.trigger_apple_gathering_client.wait_for_service(timeout_sec=1.0)) \
         while (not self.trigger_apple_gathering_client.wait_for_service(timeout_sec=1.0)) \
                 and (not self.cancel_apple_gathering_client.wait_for_service(timeout_sec=1.0)):
                 and (not self.cancel_apple_gathering_client.wait_for_service(timeout_sec=1.0)):
             self.get_logger().info('Apple gathering services not available waiting again...')
             self.get_logger().info('Apple gathering services not available waiting again...')
 
 
     def init_apple_subscriptions(self):
     def init_apple_subscriptions(self):
-        """"
-        Initialize apple gathering progress topic subsrciptions, listened by this node. 
-        """
+        """Initialize apple gathering progress topic subscription."""
         qos = QoSProfile(
         qos = QoSProfile(
             depth=5,
             depth=5,
             history=QoSHistoryPolicy.KEEP_LAST,
             history=QoSHistoryPolicy.KEEP_LAST,
             reliability=QoSReliabilityPolicy.RELIABLE,
             reliability=QoSReliabilityPolicy.RELIABLE,
             durability=QoSDurabilityPolicy.VOLATILE
             durability=QoSDurabilityPolicy.VOLATILE
         )
         )
-        self.progress_apple_gathering_sub = self.create_subscription(Float32,
-                                                                     f'{self.kraken_name}/progress_apple_gathering',
-                                                                     self.apple_progress_callback, qos)
+        self.progress_apple_gathering_sub = self.create_subscription(
+            Float32,
+            f'{self.kraken_name}/progress_apple_gathering',
+            self.apple_progress_callback, qos)
 
 
     def init_goal_pose_publisher(self):
     def init_goal_pose_publisher(self):
-        """"
-        Initialize goal topic subsrciptions, listened by this node. 
-        """
+        """Initialize goal topic subscription, listened by this node."""
         qos = QoSProfile(
         qos = QoSProfile(
             depth=5,
             depth=5,
             history=QoSHistoryPolicy.KEEP_LAST,
             history=QoSHistoryPolicy.KEEP_LAST,
@@ -105,24 +97,26 @@ class KrakenOrchestrationNode(Node):
             durability=QoSDurabilityPolicy.VOLATILE
             durability=QoSDurabilityPolicy.VOLATILE
         )
         )
 
 
-        self.goal_pose_publisher = self.create_publisher(PoseStamped, f'{self.kraken_name}/goal_pose', qos)
+        self.goal_pose_publisher = self.create_publisher(
+            PoseStamped,
+            f'{self.kraken_name}/goal_pose', qos
+        )
 
 
     def init_status_publisher(self):
     def init_status_publisher(self):
-        """"
-        Initialize topic pusblishers, sent by this node. 
-        """
+        """Initialize topic publishers, sent by this node."""
         qos = QoSProfile(
         qos = QoSProfile(
             depth=5,
             depth=5,
             history=QoSHistoryPolicy.KEEP_LAST,
             history=QoSHistoryPolicy.KEEP_LAST,
             reliability=QoSReliabilityPolicy.RELIABLE,
             reliability=QoSReliabilityPolicy.RELIABLE,
             durability=QoSDurabilityPolicy.VOLATILE
             durability=QoSDurabilityPolicy.VOLATILE
         )
         )
-        self.status_publisher = self.create_publisher(String, f'{self.kraken_name}/orchestration_status', qos)
+        self.status_publisher = self.create_publisher(
+            String,
+            f'{self.kraken_name}/orchestration_status', qos
+        )
 
 
     def send_state(self, status_str):
     def send_state(self, status_str):
-        """"
-        Publish status message which is presented by simulator's GUI
-        """
+        """Publish status message which is presented by the Simulator's GUI."""
         msg = String()
         msg = String()
         msg.data = status_str
         msg.data = status_str
         self.status_publisher.publish(msg)
         self.status_publisher.publish(msg)
@@ -149,17 +143,13 @@ class KrakenOrchestrationNode(Node):
         self.init_apple_subscriptions()
         self.init_apple_subscriptions()
 
 
     def log_cb(self, msg):
     def log_cb(self, msg):
-        """"
-        Implementation of the callback for message sent from nav2, used to find if navigation has succeed.
-        """
+        """Is called for messages sent from nav2, used to find if navigation has succeed."""
         if msg.msg == "Goal succeeded" and self.kraken_name in str(msg.name):
         if msg.msg == "Goal succeeded" and self.kraken_name in str(msg.name):
             self.get_logger().info("Navigation point reached.")
             self.get_logger().info("Navigation point reached.")
             self.goal_pose_reached = True
             self.goal_pose_reached = True
 
 
     def spawn_kraken(self):
     def spawn_kraken(self):
-        """
-        Spawn robot by calling service
-        """
+        """Spawn robot by calling service."""
         req = SpawnEntity.Request()
         req = SpawnEntity.Request()
         req.name = self.kraken_name[:len(self.kraken_name) - 2]
         req.name = self.kraken_name[:len(self.kraken_name) - 2]
         req.xml = self.spawn_point
         req.xml = self.spawn_point
@@ -171,9 +161,7 @@ class KrakenOrchestrationNode(Node):
         return res.success
         return res.success
 
 
     def get_spawn_point_pose(self):
     def get_spawn_point_pose(self):
-        """
-        Retrieve spawn points from the Simulation.
-        """
+        """Retrieve spawn points from the Simulation."""
         req = GetModelState.Request()
         req = GetModelState.Request()
         req.model_name = self.spawn_point
         req.model_name = self.spawn_point
 
 
@@ -182,9 +170,7 @@ class KrakenOrchestrationNode(Node):
         return res.pose  # TODO - Add exception handling
         return res.pose  # TODO - Add exception handling
 
 
     def get_plan_poses(self, pose):
     def get_plan_poses(self, pose):
-        """
-        Retrieve plan from the Simulation.
-        """
+        """Retrieve plan from the Simulation."""
         req = GetPlan.Request()
         req = GetPlan.Request()
         req.start.pose = pose
         req.start.pose = pose
 
 
@@ -192,23 +178,17 @@ class KrakenOrchestrationNode(Node):
         return res.plan.poses
         return res.plan.poses
 
 
     def trigger_apple_gathering(self):
     def trigger_apple_gathering(self):
-        """"
-        Calls service the Simulation to start apple gathering.
-        """
+        """Call service the Simulation to start apple gathering."""
         self.gathering_done = False
         self.gathering_done = False
         req = Trigger.Request()
         req = Trigger.Request()
         return self.trigger_apple_gathering_client.call(req)
         return self.trigger_apple_gathering_client.call(req)
 
 
     def cancel_apple_gathering(self):
     def cancel_apple_gathering(self):
-        """"
-        Calls service the Simulation to abort apple gathering.
-        """
+        """Call service the Simulation to abort apple gathering."""
         req = Trigger.Request()
         req = Trigger.Request()
         return self.cancel_apple_gathering_client.call(req)
         return self.cancel_apple_gathering_client.call(req)
 
 
     def navigate_to_pose(self, pose):
     def navigate_to_pose(self, pose):
-        """"
-        Sets navigation goal to nav2.
-        """
+        """Set navigation goal to nav2."""
         pose.header = Header(stamp=self.get_clock().now().to_msg(), frame_id='map')
         pose.header = Header(stamp=self.get_clock().now().to_msg(), frame_id='map')
         self.goal_pose_publisher.publish(pose)
         self.goal_pose_publisher.publish(pose)

+ 2 - 7
kraken_nav/o3de_kraken_orchestration/o3de_kraken_orchestration/state_machine.py

@@ -1,4 +1,3 @@
-# coding:utf-8
 #!/usr/bin/env python3
 #!/usr/bin/env python3
 
 
 #
 #
@@ -11,16 +10,12 @@
 
 
 from statemachine import StateMachine, State
 from statemachine import StateMachine, State
 
 
+
 class GlobalOrchestrationSM(StateMachine):
 class GlobalOrchestrationSM(StateMachine):
-    """
-    Orchestration state machine implementation -containst list of states and
-    valid transitions.
-    """
+    """State machine implementation, contains list of states and valid transitions."""
 
 
-    #### Members for debug purposes ###
     can_gather = False
     can_gather = False
     has_finished = True
     has_finished = True
-    ###################################
 
 
     start = State('Start', initial=True)
     start = State('Start', initial=True)
     waiting = State('Waiting')  # Waiting for the simulation start
     waiting = State('Waiting')  # Waiting for the simulation start

+ 1 - 1
kraken_nav/o3de_kraken_orchestration/package.xml

@@ -5,7 +5,7 @@
   <version>0.0.0</version>
   <version>0.0.0</version>
   <description>TODO: Package description</description>
   <description>TODO: Package description</description>
   <maintainer email="[email protected]">alekkam</maintainer>
   <maintainer email="[email protected]">alekkam</maintainer>
-  <license>TODO: License declaration</license>
+  <license>Apache 2.0</license>
 
 
   <test_depend>statemachine</test_depend>
   <test_depend>statemachine</test_depend>
 
 

+ 4 - 3
kraken_nav/o3de_kraken_orchestration/setup.py

@@ -23,12 +23,13 @@ setup(
     zip_safe=True,
     zip_safe=True,
     maintainer='alekkam',
     maintainer='alekkam',
     maintainer_email='[email protected]',
     maintainer_email='[email protected]',
-    description='TODO: Package description',
-    license='TODO: License declaration',
+    description='Orchestration code for AppleKraken robot',
+    license='Apache 2.0',
     tests_require=['pytest'],
     tests_require=['pytest'],
     entry_points={
     entry_points={
         'console_scripts': [
         'console_scripts': [
-            'kraken_orchestration_node = o3de_kraken_orchestration.global_kraken_orchestration:main'
+            'kraken_orchestration_node = '
+            'o3de_kraken_orchestration.global_kraken_orchestration:main'
         ],
         ],
     },
     },
 )
 )

+ 0 - 23
kraken_nav/o3de_kraken_orchestration/test/test_copyright.py

@@ -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_copyright.main import main
-import pytest
-
-
[email protected]
[email protected]
-def test_copyright():
-    rc = main(argv=['.', 'test'])
-    assert rc == 0, 'Found errors'