Forráskód Böngészése

Robot prefab update, navigation launchfiles

Signed-off-by: Piotr Jaroszek <[email protected]>
Piotr Jaroszek 3 éve
szülő
commit
25ba27a1c9

+ 1 - 1
.gitignore

@@ -19,4 +19,4 @@ server*.cfg
 .mayaSwatches/
 .mayaSwatches/
 _savebackup/
 _savebackup/
 *.swatches
 *.swatches
-/imgui.ini
+/imgui.ini

+ 13 - 10
Assets/RoboVac/AstroVacRobot.prefab

@@ -166,6 +166,14 @@
                                                     "guid": "{C86377E6-04B6-54CF-9909-B9392E646FA9}",
                                                     "guid": "{C86377E6-04B6-54CF-9909-B9392E646FA9}",
                                                     "subId": 1000
                                                     "subId": 1000
                                                 }
                                                 }
+                                            },
+                                            "baseColor.useTexture": {
+                                                "$type": "bool",
+                                                "Value": true
+                                            },
+                                            "baseColor.textureBlendMode": {
+                                                "$type": "unsigned int",
+                                                "Value": 3
                                             }
                                             }
                                         }
                                         }
                                     }
                                     }
@@ -2593,14 +2601,7 @@
                 "Component_[202200107630449173]": {
                 "Component_[202200107630449173]": {
                     "$type": "{27F1E1A1-8D9D-4C3B-BD3A-AFB9762449C0} TransformComponent",
                     "$type": "{27F1E1A1-8D9D-4C3B-BD3A-AFB9762449C0} TransformComponent",
                     "Id": 202200107630449173,
                     "Id": 202200107630449173,
-                    "Parent Entity": "Entity_[6506158658343]",
-                    "Transform Data": {
-                        "Translate": [
-                            56.0,
-                            37.874290466308594,
-                            -2.2000176906585693
-                        ]
-                    }
+                    "Parent Entity": "Entity_[6506158658343]"
                 },
                 },
                 "Component_[5852860452079171804]": {
                 "Component_[5852860452079171804]": {
                     "$type": "EditorVisibilityComponent",
                     "$type": "EditorVisibilityComponent",
@@ -4788,8 +4789,10 @@
                     "Id": 13195787262642532680,
                     "Id": 13195787262642532680,
                     "Configuration": {
                     "Configuration": {
                         "entityId": "",
                         "entityId": "",
+                        "Linear damping": 0.009999999776482582,
+                        "Angular damping": 0.10000000149011612,
                         "Compute Mass": false,
                         "Compute Mass": false,
-                        "Mass": 5.0,
+                        "Mass": 3.0,
                         "Centre of mass offset": [
                         "Centre of mass offset": [
                             6.424532461579702e-9,
                             6.424532461579702e-9,
                             -2.240314600499005e-9,
                             -2.240314600499005e-9,
@@ -4800,7 +4803,7 @@
                             "roll": 0.0,
                             "roll": 0.0,
                             "pitch": 0.0,
                             "pitch": 0.0,
                             "yaw": 0.0,
                             "yaw": 0.0,
-                            "scale": 0.0010974486358463764
+                            "scale": 100.0
                         }
                         }
                     }
                     }
                 },
                 },

+ 66 - 58
Levels/archvis/Loft/Interior_03.prefab

@@ -19,12 +19,12 @@
                 "$type": "EditorEntitySortComponent",
                 "$type": "EditorEntitySortComponent",
                 "Id": 14126657869720434043,
                 "Id": 14126657869720434043,
                 "Child Entity Order": [
                 "Child Entity Order": [
+                    "Instance_[2485335167382]/ContainerEntity",
                     "Entity_[2511113093496]",
                     "Entity_[2511113093496]",
                     "Entity_[4844759642882]",
                     "Entity_[4844759642882]",
                     "Entity_[4857644544770]",
                     "Entity_[4857644544770]",
                     "Entity_[50747416825914]",
                     "Entity_[50747416825914]",
-                    "Entity_[2425721989581]",
-                    "Entity_[14870551177679]"
+                    "Entity_[2425721989581]"
                 ]
                 ]
             },
             },
             "Component_[15230859088967841193]": {
             "Component_[15230859088967841193]": {
@@ -633,6 +633,13 @@
                     "$type": "EditorShapeColliderComponent",
                     "$type": "EditorShapeColliderComponent",
                     "Id": 15497122865743212243,
                     "Id": 15497122865743212243,
                     "ColliderConfiguration": {
                     "ColliderConfiguration": {
+                        "MaterialSlots": {
+                            "Slots": [
+                                {
+                                    "Name": "Entire object"
+                                }
+                            ]
+                        },
                         "MaterialSelection": {
                         "MaterialSelection": {
                             "MaterialIds": [
                             "MaterialIds": [
                                 {}
                                 {}
@@ -1018,7 +1025,56 @@
             "Components": {
             "Components": {
                 "Component_[1139584416914842089]": {
                 "Component_[1139584416914842089]": {
                     "$type": "EditorDisabledCompositionComponent",
                     "$type": "EditorDisabledCompositionComponent",
-                    "Id": 1139584416914842089
+                    "Id": 1139584416914842089,
+                    "DisabledComponents": [
+                        {
+                            "$type": "ScriptEditorComponent",
+                            "Id": 14630136217036010474,
+                            "ScriptComponent": {
+                                "Properties": {
+                                    "Properties": [
+                                        {
+                                            "$type": "AzFramework::ScriptPropertyNumber",
+                                            "id": 2278759636,
+                                            "name": "FrameCaptureCount",
+                                            "value": 100.0
+                                        },
+                                        {
+                                            "$type": "AzFramework::ScriptPropertyNumber",
+                                            "id": 4087794795,
+                                            "name": "FrameDelayCount",
+                                            "value": 100.0
+                                        },
+                                        {
+                                            "$type": "AzFramework::ScriptPropertyString",
+                                            "id": 3186282179,
+                                            "name": "ProfileName",
+                                            "value": "LoftSample"
+                                        },
+                                        {
+                                            "$type": "AzFramework::ScriptPropertyBoolean",
+                                            "id": 1762171146,
+                                            "name": "QuitOnComplete"
+                                        }
+                                    ]
+                                },
+                                "Script": {
+                                    "assetId": {
+                                        "guid": "{7003B5DC-6EEB-5B8A-8D6A-B7A374779C13}",
+                                        "subId": 1
+                                    },
+                                    "assetHint": "scripts/profiling/outputprofiledata.luac"
+                                }
+                            },
+                            "ScriptAsset": {
+                                "assetId": {
+                                    "guid": "{7003B5DC-6EEB-5B8A-8D6A-B7A374779C13}",
+                                    "subId": 1
+                                },
+                                "assetHint": "scripts/profiling/outputprofiledata.luac"
+                            }
+                        }
+                    ]
                 },
                 },
                 "Component_[12857517895964335700]": {
                 "Component_[12857517895964335700]": {
                     "$type": "SelectionComponent",
                     "$type": "SelectionComponent",
@@ -1033,53 +1089,6 @@
                     "$type": "EditorPendingCompositionComponent",
                     "$type": "EditorPendingCompositionComponent",
                     "Id": 13824613473265908415
                     "Id": 13824613473265908415
                 },
                 },
-                "Component_[14630136217036010474]": {
-                    "$type": "ScriptEditorComponent",
-                    "Id": 14630136217036010474,
-                    "ScriptComponent": {
-                        "Properties": {
-                            "Properties": [
-                                {
-                                    "$type": "AzFramework::ScriptPropertyNumber",
-                                    "id": 2278759636,
-                                    "name": "FrameCaptureCount",
-                                    "value": 100.0
-                                },
-                                {
-                                    "$type": "AzFramework::ScriptPropertyNumber",
-                                    "id": 4087794795,
-                                    "name": "FrameDelayCount",
-                                    "value": 100.0
-                                },
-                                {
-                                    "$type": "AzFramework::ScriptPropertyString",
-                                    "id": 3186282179,
-                                    "name": "ProfileName",
-                                    "value": "LoftSample"
-                                },
-                                {
-                                    "$type": "AzFramework::ScriptPropertyBoolean",
-                                    "id": 1762171146,
-                                    "name": "QuitOnComplete"
-                                }
-                            ]
-                        },
-                        "Script": {
-                            "assetId": {
-                                "guid": "{7003B5DC-6EEB-5B8A-8D6A-B7A374779C13}",
-                                "subId": 1
-                            },
-                            "assetHint": "scripts/profiling/outputprofiledata.luac"
-                        }
-                    },
-                    "ScriptAsset": {
-                        "assetId": {
-                            "guid": "{7003B5DC-6EEB-5B8A-8D6A-B7A374779C13}",
-                            "subId": 1
-                        },
-                        "assetHint": "scripts/profiling/outputprofiledata.luac"
-                    }
-                },
                 "Component_[14675633212452723131]": {
                 "Component_[14675633212452723131]": {
                     "$type": "EditorEntityIconComponent",
                     "$type": "EditorEntityIconComponent",
                     "Id": 14675633212452723131
                     "Id": 14675633212452723131
@@ -5165,7 +5174,6 @@
                     "Id": 3152360288513841949,
                     "Id": 3152360288513841949,
                     "Child Entity Order": [
                     "Child Entity Order": [
                         "Entity_[14870551177679]",
                         "Entity_[14870551177679]",
-                        "Instance_[2485335167382]/ContainerEntity",
                         "Instance_[13283805038176]/ContainerEntity",
                         "Instance_[13283805038176]/ContainerEntity",
                         "Entity_[4840464675586]",
                         "Entity_[4840464675586]",
                         "Entity_[2519703028088]",
                         "Entity_[2519703028088]",
@@ -5868,7 +5876,7 @@
                 {
                 {
                     "op": "replace",
                     "op": "replace",
                     "path": "/ContainerEntity/Components/Component_[10968750635921263389]/Parent Entity",
                     "path": "/ContainerEntity/Components/Component_[10968750635921263389]/Parent Entity",
-                    "value": "../Entity_[4857644544770]"
+                    "value": "../Entity_[1146574390643]"
                 },
                 },
                 {
                 {
                     "op": "replace",
                     "op": "replace",
@@ -5883,7 +5891,12 @@
                 {
                 {
                     "op": "replace",
                     "op": "replace",
                     "path": "/ContainerEntity/Components/Component_[10968750635921263389]/Transform Data/Translate/2",
                     "path": "/ContainerEntity/Components/Component_[10968750635921263389]/Transform Data/Translate/2",
-                    "value": 0.5022367835044861
+                    "value": 0.06635439395904541
+                },
+                {
+                    "op": "replace",
+                    "path": "/ContainerEntity/Components/Component_[10968750635921263389]/Transform Data/Rotate/2",
+                    "value": -46.42683410644531
                 },
                 },
                 {
                 {
                     "op": "remove",
                     "op": "remove",
@@ -5913,11 +5926,6 @@
                     "op": "replace",
                     "op": "replace",
                     "path": "/Entities/Entity_[30055431164411]/Components/Component_[13195787262642532680]/Configuration/Centre of mass offset/2",
                     "path": "/Entities/Entity_[30055431164411]/Components/Component_[13195787262642532680]/Configuration/Centre of mass offset/2",
                     "value": -7.555317482754731e-11
                     "value": -7.555317482754731e-11
-                },
-                {
-                    "op": "replace",
-                    "path": "/Entities/Entity_[30055431164411]/Components/Component_[13195787262642532680]/Configuration/Inertia tensor/scale",
-                    "value": 911.2044067382813
                 }
                 }
             ]
             ]
         },
         },

A különbségek nem kerülnek megjelenítésre, a fájl túl nagy
+ 263 - 0
launch/config/config.rviz


+ 259 - 0
launch/config/navigation_params.yaml

@@ -0,0 +1,259 @@
+bt_navigator:
+  ros__parameters:
+    use_sim_time: True
+    global_frame: map
+    robot_base_frame: base_link
+    odom_topic: /odom
+    bt_loop_duration: 10
+    default_server_timeout: 20
+    enable_groot_monitoring: True
+    groot_zmq_publisher_port: 1666
+    groot_zmq_server_port: 1667
+    plugin_lib_names:
+    - nav2_compute_path_to_pose_action_bt_node
+    - nav2_compute_path_through_poses_action_bt_node
+    - nav2_follow_path_action_bt_node
+    - nav2_back_up_action_bt_node
+    - nav2_spin_action_bt_node
+    - nav2_wait_action_bt_node
+    - nav2_clear_costmap_service_bt_node
+    - nav2_is_stuck_condition_bt_node
+    - nav2_goal_reached_condition_bt_node
+    - nav2_goal_updated_condition_bt_node
+    - nav2_initial_pose_received_condition_bt_node
+    - nav2_reinitialize_global_localization_service_bt_node
+    - nav2_rate_controller_bt_node
+    - nav2_distance_controller_bt_node
+    - nav2_speed_controller_bt_node
+    - nav2_truncate_path_action_bt_node
+    - nav2_goal_updater_node_bt_node
+    - nav2_recovery_node_bt_node
+    - nav2_pipeline_sequence_bt_node
+    - nav2_round_robin_node_bt_node
+    - nav2_transform_available_condition_bt_node
+    - nav2_time_expired_condition_bt_node
+    - nav2_distance_traveled_condition_bt_node
+    - nav2_single_trigger_bt_node
+    - nav2_is_battery_low_condition_bt_node
+    - nav2_navigate_through_poses_action_bt_node
+    - nav2_navigate_to_pose_action_bt_node
+    - nav2_remove_passed_goals_action_bt_node
+    - nav2_planner_selector_bt_node
+    - nav2_controller_selector_bt_node
+    - nav2_goal_checker_selector_bt_node
+
+bt_navigator_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+controller_server:
+  ros__parameters:
+    use_sim_time: True
+    controller_frequency: 20.0
+    min_x_velocity_threshold: 0.001
+    min_y_velocity_threshold: 0.5
+    min_theta_velocity_threshold: 0.001
+    failure_tolerance: 0.3
+    progress_checker_plugin: "progress_checker"
+    goal_checker_plugins: ["general_goal_checker"]
+    controller_plugins: ["FollowPath"]
+    progress_checker:
+      plugin: "nav2_controller::SimpleProgressChecker"
+      required_movement_radius: 0.5
+      movement_time_allowance: 10.0
+    general_goal_checker:
+      stateful: True
+      plugin: "nav2_controller::SimpleGoalChecker"
+      xy_goal_tolerance: 0.25
+      yaw_goal_tolerance: 0.25
+    # DWB parameters
+    FollowPath:
+      plugin: "dwb_core::DWBLocalPlanner"
+      debug_trajectory_details: True
+      min_vel_x: 0.0
+      min_vel_y: 0.0
+      max_vel_x: 1.0
+      max_vel_y: 0.0
+      max_vel_theta: 1.0
+      min_speed_xy: 0.0
+      max_speed_xy: 1.0
+      min_speed_theta: 0.0
+      acc_lim_x: 2.5
+      acc_lim_y: 0.0
+      acc_lim_theta: 3.2
+      decel_lim_x: -2.5
+      decel_lim_y: 0.0
+      decel_lim_theta: -3.2
+      vx_samples: 20
+      vy_samples: 5
+      vtheta_samples: 20
+      sim_time: 1.7
+      linear_granularity: 0.05
+      angular_granularity: 0.025
+      transform_tolerance: 0.2
+      xy_goal_tolerance: 0.25
+      trans_stopped_velocity: 0.25
+      short_circuit_trajectory_evaluation: True
+      stateful: True
+      critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+      BaseObstacle.scale: 0.02
+      PathAlign.scale: 2.0
+      PathAlign.forward_point_distance: 0.1
+      GoalAlign.scale: 1.0
+      GoalAlign.forward_point_distance: 0.1
+      PathDist.scale: 1.0
+      GoalDist.scale: 1.0
+      RotateToGoal.scale: 2.0
+      RotateToGoal.slowing_factor: 5.0
+      RotateToGoal.lookahead_time: -1.0
+      
+controller_server_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      update_frequency: 5.0
+      publish_frequency: 2.0
+      global_frame: odom
+      robot_base_frame: base_link
+      use_sim_time: True
+      rolling_window: true
+      width: 5
+      height: 5
+      resolution: 0.02
+      robot_radius: 0.25
+      plugins: ["voxel_layer", "inflation_layer"]
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 10.0
+        inflation_radius: 0.55
+      voxel_layer:
+        plugin: "nav2_costmap_2d::VoxelLayer"
+        enabled: True
+        publish_voxel_map: True
+        origin_z: 0.0
+        z_resolution: 0.05
+        z_voxels: 16
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: scan
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+  local_costmap_client:
+    ros__parameters:
+      use_sim_time: True
+  local_costmap_rclcpp_node:
+    ros__parameters:
+      use_sim_time: True
+
+global_costmap:
+  global_costmap:
+    ros__parameters:
+      update_frequency: 1.0
+      publish_frequency: 1.0
+      global_frame: map
+      robot_base_frame: base_link
+      use_sim_time: True
+      robot_radius: 0.25
+      resolution: 0.02
+      track_unknown_space: true
+      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
+      obstacle_layer:
+        plugin: "nav2_costmap_2d::ObstacleLayer"
+        enabled: True
+        observation_sources: scan
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        plugin: "nav2_costmap_2d::StaticLayer"
+        map_subscribe_transient_local: True
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.4
+      always_send_full_costmap: True
+  global_costmap_client:
+    ros__parameters:
+      use_sim_time: True
+  global_costmap_rclcpp_node:
+    ros__parameters:
+      use_sim_time: True
+
+map_saver:
+  ros__parameters:
+    use_sim_time: True
+    save_map_timeout: 5.0
+    free_thresh_default: 0.25
+    occupied_thresh_default: 0.65
+    map_subscribe_transient_local: True
+
+planner_server:
+  ros__parameters:
+    expected_planner_frequency: 20.0
+    use_sim_time: True
+    planner_plugins: ["GridBased"]
+    GridBased:
+      plugin: "nav2_navfn_planner/NavfnPlanner"
+      tolerance: 0.5
+      use_astar: true
+      allow_unknown: true
+
+planner_server_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+recoveries_server:
+  ros__parameters:
+    costmap_topic: local_costmap/costmap_raw
+    footprint_topic: local_costmap/published_footprint
+    cycle_frequency: 10.0
+    recovery_plugins: ["spin", "backup", "wait"]
+    spin:
+      plugin: "nav2_recoveries/Spin"
+    backup:
+      plugin: "nav2_recoveries/BackUp"
+    wait:
+      plugin: "nav2_recoveries/Wait"
+    global_frame: odom
+    robot_base_frame: base_link
+    transform_timeout: 0.1
+    use_sim_time: true
+    simulate_ahead_time: 2.0
+    max_rotational_vel: 1.0
+    min_rotational_vel: 0.4
+    rotational_acc_lim: 3.2
+
+robot_state_publisher:
+  ros__parameters:
+    use_sim_time: True
+
+waypoint_follower:
+  ros__parameters:
+    loop_rate: 20
+    stop_on_failure: false
+    waypoint_task_executor_plugin: "wait_at_waypoint"   
+    wait_at_waypoint:
+      plugin: "nav2_waypoint_follower::WaitAtWaypoint"
+      enabled: True
+      waypoint_pause_duration: 200

+ 73 - 0
launch/config/slam_params.yaml

@@ -0,0 +1,73 @@
+slam_toolbox:
+  ros__parameters:
+
+    # Plugin params
+    solver_plugin: solver_plugins::CeresSolver
+    ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
+    ceres_preconditioner: SCHUR_JACOBI
+    ceres_trust_strategy: LEVENBERG_MARQUARDT
+    ceres_dogleg_type: TRADITIONAL_DOGLEG
+    ceres_loss_function: None
+
+    # ROS Parameters
+    odom_frame: odom
+    map_frame: map
+    base_frame: base_link
+    scan_topic: /scan
+    mode: mapping #localization
+
+    # if you'd like to immediately start continuing a map at a given pose
+    # or at the dock, but they are mutually exclusive, if pose is given
+    # will use pose
+    #map_file_name: test_steve
+    # map_start_pose: [0.0, 0.0, 0.0]
+    #map_start_at_dock: true
+
+    debug_logging: false
+    throttle_scans: 1
+    transform_publish_period: 0.02 #if 0 never publishes odometry
+    map_update_interval: 5.0
+    resolution: 0.05
+    max_laser_range: 20.0 #for rastering images
+    minimum_time_interval: 0.5
+    transform_timeout: 0.2
+    tf_buffer_duration: 30.
+    stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
+    enable_interactive_mode: true
+
+    # General Parameters
+    use_scan_matching: true
+    use_scan_barycenter: true
+    minimum_travel_distance: 0.5
+    minimum_travel_heading: 0.5
+    scan_buffer_size: 10
+    scan_buffer_maximum_scan_distance: 10.0
+    link_match_minimum_response_fine: 0.1  
+    link_scan_maximum_distance: 1.5
+    loop_search_maximum_distance: 3.0
+    do_loop_closing: true 
+    loop_match_minimum_chain_size: 10           
+    loop_match_maximum_variance_coarse: 3.0  
+    loop_match_minimum_response_coarse: 0.35    
+    loop_match_minimum_response_fine: 0.45
+
+    # Correlation Parameters - Correlation Parameters
+    correlation_search_space_dimension: 0.5
+    correlation_search_space_resolution: 0.01
+    correlation_search_space_smear_deviation: 0.1 
+
+    # Correlation Parameters - Loop Closure Parameters
+    loop_search_space_dimension: 8.0
+    loop_search_space_resolution: 0.05
+    loop_search_space_smear_deviation: 0.03
+
+    # Scan Matcher Parameters
+    distance_variance_penalty: 0.5      
+    angle_variance_penalty: 1.0    
+
+    fine_search_angle_offset: 0.00349     
+    coarse_search_angle_offset: 0.349   
+    coarse_angle_resolution: 0.0349        
+    minimum_angle_penalty: 0.9
+    minimum_distance_penalty: 0.5
+    use_response_expansion: true

+ 32 - 0
launch/navigation.launch.py

@@ -0,0 +1,32 @@
+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(__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(__file__).parent.absolute().joinpath('config', 'navigation_params.yaml'))
+            }.items()
+        ),
+        Node(
+            package='rviz2',
+            executable='rviz2',
+            name='slam',
+            output={
+                'stdout': 'log',
+            },
+            arguments=[
+                '-d', str(pathlib.Path(__file__).parent.absolute().joinpath('config', 'config.rviz')),
+            ]
+        ),
+    ])

+ 32 - 0
launch/slam.launch.py

@@ -0,0 +1,32 @@
+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.0,
+                'max_height': 0.5,
+                'range_min': 0.1
+            }],
+            remappings=[
+                ('/cloud_in', '/pc'),
+            ]
+        )
+    ])

Nem az összes módosított fájl került megjelenítésre, mert túl sok fájl változott