2
0
Эх сурвалжийг харах

Cleaned up launchfile

Signed-off-by: Piotr Jaroszek <[email protected]>
Piotr Jaroszek 2 жил өмнө
parent
commit
5cd2b861b1

+ 6 - 3
kraken_nav/README.md

@@ -1,5 +1,10 @@
 # Apple kraken navigation #
 
+## ROS2 package Requirements
+
+- `nav2` navigation package (NAV2)[https://navigation.ros.org/]
+- `slam_toolbox` slam toolbox
+
 ## Installation ##
 
 It is assumed that ROS2 `galactic` is used and the workspace dir is in `~/o3de_kraken_ws`.
@@ -38,9 +43,7 @@ cd ~/o3de_kraken_ws
 source ./install/setup.bash
 ```
 
-2. (This step is going to be removed) Adjust behavior tree setting `default_nav_to_pose_bt_xml` in `src/o3de_kraken_nav/launch/config/navigation_params.yaml` so it globally points to the `bt.xml` in your `o3de_kraken_nav/launch/config` directory  (line 6)
-
-3. Run the navigation stack
+2. Run the navigation stack
 
 ```bash
 ros2 launch o3de_kraken_nav navigation.launch.py

+ 1 - 3
kraken_nav/launch/config/navigation_params.yaml

@@ -1,9 +1,6 @@
 bt_navigator:
   ros__parameters:
     use_sim_time: True
-    # Set global path to bt.xml from this package 
-    # TODO - do it in launcher
-    # default_nav_to_pose_bt_xml: "bt.xml" 
     global_frame: map
     robot_base_frame: base_link
     odom_topic: /odom
@@ -16,6 +13,7 @@ bt_navigator:
     # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
     # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
     # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
+    default_nav_to_pose_bt_xml: "bt.xml" 
     plugin_lib_names:
     - nav2_compute_path_to_pose_action_bt_node
     - nav2_compute_path_through_poses_action_bt_node

+ 73 - 32
kraken_nav/launch/navigation.launch.py

@@ -1,40 +1,81 @@
 import pathlib
-
 from ament_index_python.packages import get_package_share_directory
-
 from launch import LaunchDescription
 from launch.actions import IncludeLaunchDescription
 from launch.launch_description_sources import PythonLaunchDescriptionSource
 from launch_ros.actions import Node
+from nav2_common.launch import RewrittenYaml
 
 def generate_launch_description():
-    return LaunchDescription([
-        IncludeLaunchDescription(
-            PythonLaunchDescriptionSource([str(pathlib.Path(__file__).parent.absolute().joinpath('slam.launch.py'))])
-        ),
-        IncludeLaunchDescription(
-            PythonLaunchDescriptionSource([str(pathlib.Path(get_package_share_directory("nav2_bringup")).joinpath('launch', 'navigation_launch.py'))]),
-            launch_arguments = {
-                'params_file': str(pathlib.Path(get_package_share_directory("o3de_kraken_nav")).joinpath('launch', 'config', 'navigation_params.yaml'))
-            }.items()
-        ),
-        Node(
-            package='o3de_kraken_nav',
-            executable='twist_to_ackermann',
-            name='twist_to_ackermann',
-            output={
-                'stdout': 'log'
-            }
-        ),
-        Node(
-            package='rviz2',
-            executable='rviz2',
-            name='slam',
-            output={
-                'stdout': 'log',
-            },
-            arguments=[
-                '-d', str(pathlib.Path(get_package_share_directory("o3de_kraken_nav")).joinpath('launch', 'config', 'config.rviz')),
-            ]
-        ),
-    ])
+    package_dir = get_package_share_directory("o3de_kraken_nav")
+    slam_toolbox_dir = get_package_share_directory('slam_toolbox')
+    nav2_dir = get_package_share_directory("nav2_bringup")
+
+    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'))
+
+    param_substitutions = {
+        'default_nav_to_pose_bt_xml': bt_xml_file}
+    configured_nav2_params = RewrittenYaml(
+        source_file=nav2_params_file,
+        root_key='',
+        param_rewrites=param_substitutions,
+        convert_types=True)
+    
+    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')),
+        }.items()
+    )
+    
+    navigation = IncludeLaunchDescription(
+        PythonLaunchDescriptionSource([str(pathlib.Path(nav2_dir).joinpath('launch', 'navigation_launch.py'))]),
+        launch_arguments = {
+            'params_file': configured_nav2_params,
+        }.items()
+    )
+    
+    pointcloud_to_laserscan = Node(
+        package='pointcloud_to_laserscan',
+        executable='pointcloud_to_laserscan_node',
+        name='pc_to_laserscan',
+        parameters=[{
+            'min_height': 0.2,
+            'max_height': 3.4,
+            'range_min': 0.2
+        }],
+        remappings=[
+            ('/cloud_in', '/pc'),
+        ]
+    )
+    
+    twist_to_ackermann = Node(
+        package='o3de_kraken_nav',
+        executable='twist_to_ackermann',
+        name='twist_to_ackermann',
+        output={
+            'stdout': 'log'
+        }
+    )
+    
+    rviz = Node(
+        package='rviz2',
+        executable='rviz2',
+        name='slam',
+        output={
+            'stdout': 'log',
+        },
+        arguments=[
+            '-d', str(pathlib.Path(package_dir).joinpath('launch', 'config', 'config.rviz')),
+        ]
+    )
+    
+    ld = LaunchDescription()
+    ld.add_action(pointcloud_to_laserscan)
+    ld.add_action(twist_to_ackermann)
+    ld.add_action(slam)
+    ld.add_action(navigation)
+    ld.add_action(rviz)
+    
+    return ld

+ 0 - 32
kraken_nav/launch/slam.launch.py

@@ -1,32 +0,0 @@
-import pathlib
-
-from ament_index_python.packages import get_package_share_directory
-
-from launch import LaunchDescription
-from launch.actions import IncludeLaunchDescription
-from launch.launch_description_sources import PythonLaunchDescriptionSource
-from launch_ros.actions import Node
-
-def generate_launch_description():
-    return LaunchDescription([
-        IncludeLaunchDescription(
-            PythonLaunchDescriptionSource([str(pathlib.Path(
-                get_package_share_directory('slam_toolbox')).joinpath('launch', 'online_async_launch.py'))]),
-            launch_arguments = {
-                'slam_params_file': str(pathlib.Path(__file__).parent.absolute().joinpath('config', 'slam_params.yaml'))
-            }.items()
-        ),
-        Node(
-            package='pointcloud_to_laserscan',
-            executable='pointcloud_to_laserscan_node',
-            name='pc_to_laserscan',
-            parameters=[{
-                'min_height': 0.2,
-                'max_height': 3.4,
-                'range_min': 0.2
-            }],
-            remappings=[
-                ('/cloud_in', '/pc'),
-            ]
-        )
-    ])

+ 0 - 1
kraken_nav/o3de_kraken_nav/twist_to_ackermann.py

@@ -24,7 +24,6 @@ class TwistToAckermann(Node):
   def cmd_vel_cb(self, data):
     vel = data.linear.x
     steering = self.twist_to_ackermann(vel, data.angular.z)
-    # print(f"v: {vel} steering: {steering}")
     
     msg = AckermannDrive()
     msg.steering_angle = float(steering)