From 2bfca8a844528f86b20191f955b219988ffbfe37 Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Fri, 20 Sep 2024 10:49:45 -0700 Subject: [PATCH] Updates for Isaac Sim 4.2.0 --- CHANGELOG.md | 13 + .../isaac_tutorials/rviz2/carter_stereo.rviz | 104 +-- .../isaacsim/launch/run_isaacsim.launch.py | 2 +- foxy_ws/src/isaacsim/package.xml | 2 +- foxy_ws/src/isaacsim/scripts/run_isaacsim.py | 4 +- .../carter_navigation_isaacsim.launch.py | 4 +- .../navigation/carter_navigation/package.xml | 2 +- .../iw_hub_navigation/CMakeLists.txt | 13 + .../launch/iw_hub_navigation.launch.py | 58 ++ .../iw_hub_navigation_isaacsim.launch.py | 103 +++ .../maps/iw_hub_warehouse_navigation.png | Bin 0 -> 5023 bytes .../maps/iw_hub_warehouse_navigation.yaml | 6 + .../navigation/iw_hub_navigation/package.xml | 55 ++ .../params/iw_hub_navigation_params.yaml | 327 +++++++++ .../rviz2/iw_hub_navigation.rviz | 590 ++++++++++++++++ .../isaac_tutorials/rviz2/carter_stereo.rviz | 147 +++- .../isaacsim/launch/run_isaacsim.launch.py | 2 +- .../src/isaacsim/scripts/run_isaacsim.py | 4 +- .../carter_navigation_isaacsim.launch.py | 4 +- .../rviz2/carter_navigation.rviz | 149 +++- .../iw_hub_navigation/CMakeLists.txt | 13 + .../launch/iw_hub_navigation.launch.py | 58 ++ .../iw_hub_navigation_isaacsim.launch.py | 103 +++ .../maps/iw_hub_warehouse_navigation.png | Bin 0 -> 5023 bytes .../maps/iw_hub_warehouse_navigation.yaml | 6 + .../navigation/iw_hub_navigation/package.xml | 56 ++ .../params/iw_hub_navigation_params.yaml | 384 ++++++++++ .../rviz2/iw_hub_navigation.rviz | 667 ++++++++++++++++++ .../isaac_tutorials/rviz/camera_lidar.rviz | 133 ++-- .../isaac_tutorials/rviz/turtle_stereo.rviz | 122 ---- .../rviz/turtlebot_config.rviz} | 404 ++++------- .../launch/carter_navigation.launch | 28 + .../launch/carter_navigation_rtx.launch | 56 -- .../launch/carter_slam_gmapping.launch | 33 + .../launch/move_base_individual.launch | 27 + .../src/navigation/carter_2dnav/package.xml | 2 +- .../rviz/carter_slam_gmapping.rviz | 234 ++++++ ubuntu_20_foxy_minimal.dockerfile | 5 +- ubuntu_20_humble_minimal.dockerfile | 5 +- 39 files changed, 3305 insertions(+), 620 deletions(-) create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/CMakeLists.txt create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.png create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.yaml create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/package.xml create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml create mode 100644 foxy_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz create mode 100644 humble_ws/src/navigation/iw_hub_navigation/CMakeLists.txt create mode 100644 humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py create mode 100644 humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py create mode 100644 humble_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.png create mode 100644 humble_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.yaml create mode 100644 humble_ws/src/navigation/iw_hub_navigation/package.xml create mode 100644 humble_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml create mode 100644 humble_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz delete mode 100644 noetic_ws/src/isaac_tutorials/rviz/turtle_stereo.rviz rename noetic_ws/src/{navigation/carter_2dnav/rviz/carter_2dnav_rtx.rviz => isaac_tutorials/rviz/turtlebot_config.rviz} (50%) delete mode 100644 noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation_rtx.launch create mode 100644 noetic_ws/src/navigation/carter_2dnav/launch/carter_slam_gmapping.launch create mode 100644 noetic_ws/src/navigation/carter_2dnav/rviz/carter_slam_gmapping.rviz diff --git a/CHANGELOG.md b/CHANGELOG.md index 5ddb72a..65b39cf 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,18 @@ # Changelog +## [2.0.0] - 2024-09-20 + +### Added +- New `iw_hub_navigation` package to run Nav2 with new iw.hub robot in new environment [Foxy, Humble] +- New RViz config for TurtleBot tutorials [Noetic] +- New RViz config and launch file with Carter robot for SLAM with gmapping + +### Changed +- Bumped versions in `isaacsim` package to Isaac Sim version 4.2.0 [Foxy, Humble] +- Changed `carter_2dnav` package to only use RTX Lidar [Noetic] +- Updated dockerfiles to use setuptools 70.0.0 [Humble, Foxy] +- Updated QoS settings for image subscribers in ``carter_stereo.rviz`` and ``carter_navigation.rviz`` config files. [Foxy, Humble] + ## [1.1.0] - 2024-08-01 ### Added diff --git a/foxy_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz b/foxy_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz index 23355ad..0ec4e75 100644 --- a/foxy_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz +++ b/foxy_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz @@ -7,9 +7,14 @@ Panels: - /Global Options1 - /Status1 - /TF1 - - /Odometry1/Topic1 + - /Left Camera - RGB1 + - /Left Camera - RGB1/Topic1 + - /Right Camera - RGB1 + - /Right Camera - RGB1/Topic1 + - /PointCloud21 + - /PointCloud21/Topic1 Splitter Ratio: 0.5 - Tree Height: 469 + Tree Height: 415 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -49,82 +54,13 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true - base_link: - Value: true - chassis_link: - Value: true - front_2d_lidar: - Value: true - front_3d_lidar: - Value: true - front_stereo_camera_imu: - Value: true - front_stereo_camera_left_optical: - Value: true - front_stereo_camera_right_optical: - Value: true - left_stereo_camera_imu: - Value: true - left_stereo_camera_left_optical: - Value: true - left_stereo_camera_right_optical: - Value: true - odom: - Value: true - rear_2d_lidar: - Value: true - rear_stereo_camera:imu: - Value: true - rear_stereo_camera:left_rgb: - Value: true - rear_stereo_camera:right_rgb: - Value: true - right_stereo_camera_imu: - Value: true - right_stereo_camera_left_optical: - Value: true - right_stereo_camera_right_optical: - Value: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: false Tree: - odom: - base_link: - chassis_link: - {} - front_2d_lidar: - {} - front_3d_lidar: - {} - front_stereo_camera_imu: - {} - front_stereo_camera_left_optical: - {} - front_stereo_camera_right_optical: - {} - left_stereo_camera_imu: - {} - left_stereo_camera_left_optical: - {} - left_stereo_camera_right_optical: - {} - rear_2d_lidar: - {} - rear_stereo_camera:imu: - {} - rear_stereo_camera:left_rgb: - {} - rear_stereo_camera:right_rgb: - {} - right_stereo_camera_imu: - {} - right_stereo_camera_left_optical: - {} - right_stereo_camera_right_optical: - {} + {} Update Interval: 0 Value: true - Angle Tolerance: 0.10000000149011612 @@ -176,7 +112,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /front_stereo_camera/left/image_raw Value: true - Class: rviz_default_plugins/Image @@ -190,7 +126,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /front_stereo_camera/right/image_raw Value: true - Alpha: 1 @@ -221,7 +157,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /front_3d_lidar/lidar_points Use Fixed Frame: true Use rainbow: true @@ -269,16 +205,16 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 7.74399995803833 + Distance: 17.497577667236328 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0.08670726418495178 - Y: -0.48873579502105713 - Z: 2.1064507961273193 + X: -1.3069220781326294 + Y: 2.1997342109680176 + Z: -0.3324333727359772 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false @@ -292,12 +228,12 @@ Visualization Manager: Window Geometry: Displays: collapsed: false - Height: 752 + Height: 704 Hide Left Dock: false Hide Right Dock: true Left Camera - RGB: collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000001880000029afc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b0000029a000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002800520069006700680074002000430061006d0065007200610020002d0020004400650070007400680200000285000002b4000002390000017ffb00000026004c006500660074002000430061006d0065007200610020002d0020004400650070007400680200000227000002b70000023c00000181fb00000022004c006500660074002000430061006d0065007200610020002d0020005200470042030000030e000001200000016b000000fafb0000002400520069006700680074002000430061006d0065007200610020002d002000520047004203000005360000011f00000169000000fbfb0000000a0049006d006100670065030000236c0000040e0000023e0000017e000000010000015f0000029afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b0000029a000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000003dd0000029a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd00000004000000000000022700000266fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000266000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002800520069006700680074002000430061006d0065007200610020002d0020004400650070007400680200000285000002b4000002390000017ffb00000026004c006500660074002000430061006d0065007200610020002d0020004400650070007400680200000227000002b70000023c00000181fb00000022004c006500660074002000430061006d0065007200610020002d00200052004700420300000270000000c80000016b000000fafb0000002400520069006700680074002000430061006d0065007200610020002d002000520047004203000002930000020500000169000000fbfb0000000a0049006d006100670065030000236c0000040e0000023e0000017e000000010000015f0000029afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b0000029a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000018b0000026600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Right Camera - RGB: collapsed: false Selection: @@ -306,6 +242,6 @@ Window Geometry: collapsed: false Views: collapsed: true - Width: 1387 - X: 344 - Y: 122 + Width: 952 + X: 72 + Y: 27 diff --git a/foxy_ws/src/isaacsim/launch/run_isaacsim.launch.py b/foxy_ws/src/isaacsim/launch/run_isaacsim.launch.py index 314d0cc..f0d5bcc 100644 --- a/foxy_ws/src/isaacsim/launch/run_isaacsim.launch.py +++ b/foxy_ws/src/isaacsim/launch/run_isaacsim.launch.py @@ -16,7 +16,7 @@ # Declare all launch arguments corresponding to the bash script options launch_args = [ - DeclareLaunchArgument('version', default_value='4.1.0', description='Specify the version of Isaac Sim to use. Isaac Sim will be run from default install root folder for the specified version. Leave empty to use latest version of Isaac Sim.'), + DeclareLaunchArgument('version', default_value='4.2.0', description='Specify the version of Isaac Sim to use. Isaac Sim will be run from default install root folder for the specified version. Leave empty to use latest version of Isaac Sim.'), DeclareLaunchArgument('install_path', default_value='', description='If Isaac Sim is insalled in a non-default location, provide a specific path to Isaac Sim installation root folder. (If defined, "version" parameter will be ignored)'), diff --git a/foxy_ws/src/isaacsim/package.xml b/foxy_ws/src/isaacsim/package.xml index d5f2f87..fb6c489 100644 --- a/foxy_ws/src/isaacsim/package.xml +++ b/foxy_ws/src/isaacsim/package.xml @@ -2,7 +2,7 @@ isaacsim - 0.1.0 + 0.2.0 The isaacsim package that contains the script which can used to launch Isaac Sim as a ROS2 node from a launch file. diff --git a/foxy_ws/src/isaacsim/scripts/run_isaacsim.py b/foxy_ws/src/isaacsim/scripts/run_isaacsim.py index 93a2f1e..80285ec 100755 --- a/foxy_ws/src/isaacsim/scripts/run_isaacsim.py +++ b/foxy_ws/src/isaacsim/scripts/run_isaacsim.py @@ -20,7 +20,7 @@ # Default values defaults = { - "isaac_sim_version": "4.1.0", + "isaac_sim_version": "4.2.0", "isaac_sim_path": "", "use_internal_libs": False, "dds_type": "fastdds", @@ -106,7 +106,7 @@ def execute_launch(self): # If custom Isaac Sim Installation folder not given, use the default path using version number provided. home_var = "USERPROFILE" if sys.platform == "win32" else "HOME" home_path = os.getenv(home_var) - if version_ge(args.version, "4.1.0") and not version_gt(args.version, "2021.2.0"): + if version_ge(args.version, "4.2.0") and not version_gt(args.version, "2021.2.0"): if sys.platform == "win32": filepath_root = os.path.join(home_path, "AppData", "Local", "ov", "pkg", f"isaac-sim-{args.version}") else: diff --git a/foxy_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py b/foxy_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py index 556c01e..b6e52c1 100644 --- a/foxy_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py +++ b/foxy_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py @@ -63,7 +63,7 @@ def execute_second_node_if_condition_met(event, second_node_action): return LaunchDescription( [ # Declaring the Isaac Sim scene path. 'gui' launch argument is already used withing run_isaac_sim.launch.py - DeclareLaunchArgument("gui", default_value='omniverse://localhost/NVIDIA/Assets/Isaac/4.1/Isaac/Samples/ROS2/Scenario/carter_warehouse_navigation.usd', description="Path to isaac sim scene"), + DeclareLaunchArgument("gui", default_value='omniverse://localhost/NVIDIA/Assets/Isaac/4.2/Isaac/Samples/ROS2/Scenario/carter_warehouse_navigation.usd', description="Path to isaac sim scene"), # Include Isaac Sim launch file from isaacsim package with given launch parameters. IncludeLaunchDescription( @@ -73,7 +73,7 @@ def execute_second_node_if_condition_met(event, second_node_action): ] ), launch_arguments={ - 'version': '4.1.0', + 'version': '4.2.0', 'play_sim_on_start': 'true', }.items(), ), diff --git a/foxy_ws/src/navigation/carter_navigation/package.xml b/foxy_ws/src/navigation/carter_navigation/package.xml index e13f017..c28701b 100644 --- a/foxy_ws/src/navigation/carter_navigation/package.xml +++ b/foxy_ws/src/navigation/carter_navigation/package.xml @@ -2,7 +2,7 @@ carter_navigation - 0.1.0 + 0.1.1 The carter_navigation package diff --git a/foxy_ws/src/navigation/iw_hub_navigation/CMakeLists.txt b/foxy_ws/src/navigation/iw_hub_navigation/CMakeLists.txt new file mode 100644 index 0000000..dc12c87 --- /dev/null +++ b/foxy_ws/src/navigation/iw_hub_navigation/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 3.5) +project(iw_hub_navigation) + +find_package(ament_cmake REQUIRED) + +install(DIRECTORY + launch + params + maps + rviz2 + DESTINATION share/${PROJECT_NAME}) + +ament_package() diff --git a/foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py b/foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py new file mode 100644 index 0000000..a24103d --- /dev/null +++ b/foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py @@ -0,0 +1,58 @@ +## Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. +## NVIDIA CORPORATION and its licensors retain all intellectual property +## and proprietary rights in and to this software, related documentation +## and any modifications thereto. Any use, reproduction, disclosure or +## distribution of this software and related documentation without an express +## license agreement from NVIDIA CORPORATION is strictly prohibited. + +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + + use_sim_time = LaunchConfiguration("use_sim_time", default="True") + + map_dir = LaunchConfiguration( + "map", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "maps", "iw_hub_warehouse_navigation.yaml" + ), + ) + + param_dir = LaunchConfiguration( + "params_file", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "params", "iw_hub_navigation_params.yaml" + ), + ) + + nav2_bringup_launch_dir = os.path.join(get_package_share_directory("nav2_bringup"), "launch") + + rviz_config_dir = os.path.join(get_package_share_directory("iw_hub_navigation"), "rviz2", "iw_hub_navigation.rviz") + + return LaunchDescription( + [ + DeclareLaunchArgument("map", default_value=map_dir, description="Full path to map file to load"), + DeclareLaunchArgument( + "params_file", default_value=param_dir, description="Full path to param file to load" + ), + DeclareLaunchArgument( + "use_sim_time", default_value="true", description="Use simulation (Omniverse Isaac Sim) clock if true" + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(nav2_bringup_launch_dir, "rviz_launch.py")), + launch_arguments={"namespace": "", "use_namespace": "False", "rviz_config": rviz_config_dir}.items(), + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource([nav2_bringup_launch_dir, "/bringup_launch.py"]), + launch_arguments={"map": map_dir, "use_sim_time": use_sim_time, "params_file": param_dir}.items(), + ), + ] + ) diff --git a/foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py b/foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py new file mode 100644 index 0000000..0ee14d3 --- /dev/null +++ b/foxy_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py @@ -0,0 +1,103 @@ +## Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. +## NVIDIA CORPORATION and its licensors retain all intellectual property +## and proprietary rights in and to this software, related documentation +## and any modifications thereto. Any use, reproduction, disclosure or +## distribution of this software and related documentation without an express +## license agreement from NVIDIA CORPORATION is strictly prohibited. + +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node +from launch.actions import RegisterEventHandler, ExecuteProcess +from launch.event_handlers import OnProcessStart, OnProcessIO +from launch.substitutions import FindExecutable + +def generate_launch_description(): + + use_sim_time = LaunchConfiguration("use_sim_time", default="True") + + map_dir = LaunchConfiguration( + "map", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "maps", "iw_hub_warehouse_navigation.yaml" + ), + ) + + param_dir = LaunchConfiguration( + "params_file", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "params", "iw_hub_navigation_params.yaml" + ), + ) + + + nav2_bringup_launch_dir = os.path.join(get_package_share_directory("nav2_bringup"), "launch") + + rviz_config_dir = os.path.join(get_package_share_directory("iw_hub_navigation"), "rviz2", "iw_hub_navigation.rviz") + + ld_automatic_goal = IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory("isaac_ros_navigation_goal"), "launch", "isaac_ros_navigation_goal.launch.py" + ), + ] + ), + ) + + + + def execute_second_node_if_condition_met(event, second_node_action): + output = event.text.decode().strip() + # Look for fully loaded message from Isaac Sim. Only applicable in Gui mode. + if "Stage loaded and simulation is playing." in output: + # Log a message indicating the condition has been met + print("Condition met, launching the second node.") + + return second_node_action + + + return LaunchDescription( + [ + # Declaring the Isaac Sim scene path. 'gui' launch argument is already used withing run_isaac_sim.launch.py + DeclareLaunchArgument("gui", default_value='omniverse://localhost/NVIDIA/Assets/Isaac/4.2/Isaac/Samples/ROS2/Scenario/iw_hub_warehouse_navigation.usd', description="Path to isaac sim scene"), + + # Include Isaac Sim launch file from isaacsim package with given launch parameters. + IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory("isaacsim"), "launch", "run_isaacsim.launch.py" + ), + ] + ), + launch_arguments={ + 'version': '4.2.0', + 'play_sim_on_start': 'true', + }.items(), + ), + + DeclareLaunchArgument("map", default_value=map_dir, description="Full path to map file to load"), + DeclareLaunchArgument( + "params_file", default_value=param_dir, description="Full path to param file to load" + ), + DeclareLaunchArgument( + "use_sim_time", default_value="true", description="Use simulation (Omniverse Isaac Sim) clock if true" + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(nav2_bringup_launch_dir, "rviz_launch.py")), + launch_arguments={"namespace": "", "use_namespace": "False", "rviz_config": rviz_config_dir}.items(), + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource([nav2_bringup_launch_dir, "/bringup_launch.py"]), + launch_arguments={"map": map_dir, "use_sim_time": use_sim_time, "params_file": param_dir}.items(), + ), + # Launch automatic goal generator node when Isaac Sim has finished loading. + RegisterEventHandler( + OnProcessIO( + on_stdout=lambda event: execute_second_node_if_condition_met(event, ld_automatic_goal) + ) + ), + ] + ) diff --git a/foxy_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.png b/foxy_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.png new file mode 100644 index 0000000000000000000000000000000000000000..9f477db1a5c3798348401bb3ad407d171ce6cdb1 GIT binary patch literal 5023 zcmeHLdr(tX9zHkW6%3(-vVsQiQBW3^1cE#SiK0R&_*iF4i}Hw%h*W`;fCPC3R1ljH zQAZM`u`FArTPesxUJ|^31zlnSixMFSB9Nd!jb0Woy!L>PsWa_PcV_GCv}W>0a_5|T z?m6G@d;D(Z_N_h!`b+cy00zDvZrT9=js^hUUQY*J(cS3={}}K0-L&B^+}zRo5mA=| zmaPA?>0rvrWH&7D*_TcwdsU}y@9w|)w~s16+nN6usW7Apb6B0$fOmS1-va=zmrMie zPw@~CtwjW3&Aa_*{F!rMO|b<@1ST%>+{LD6W|-eL_PTIiqGc z*>qvNXfqMS5d>Gn+r}DjynMDX_2rr8oaR>hP}fy&Fy#3JroKd@pG?l^vsnc!SlYi8 z6eKOBhw?oWgXPy4Wf6_ehCDDIK|DMd@rFGWhg7Yp48Q3YsU`1>`DJoW{YR zzG>9Se42db?qc3VS;WPDMx6OtCICgR%aUYH%j(V~q16&>WKtH~h*x&pAF#;Ab31yfmm*Nn{{h`ENuEK>_w``ES{dL|&*QC7z8%j(NH4M4KrtAcm)N4fh* zfO}^*ZvTZ%M4%RI)FuLSg z!1_fpOfqw8G45U#FO$nEcO7~bnMmMyA{;iUTum9ba$QU;>Kb_)ukzF&-U z)kTc^vOfcpmPn&Z-5MM_2A3XHILToC4cOG{!K_}2k{2|a9&sM^YerZc}(Zf5-c zsJ}yr6j(!P)FS*=r17l2AYSAXg#&CLRv%UJwbL%1rZ(Ox)aOziov$dQDUNR{pb-)y^`0sp{KmYBfc< zjz+2hiLs;WXtXW5RmZe|de<9<<%mGRSek_J!Y_D1?AY1*rcuhl7x;GW`Xk(K!6QH| zO*mJhvXeMM(9NvMaQ!+V(guS^^RS=uNBz&9=nGmXh?f(5;WKY|W0hZUV(*5$ktlq% zB_6VT7ev(L!GU}he~nXqJi>)1uJrGSH5U^occ2w;Z(KIKsi+W-T{pZW43iGr#cJ(Z z{N|=&tOA%75uEKxrv+Hdtc+-j50j-gUfoIuFfXi_Kx@0?2dnCQx9^AScX=B9g~|Vn zx2nAZ8O6gIl??L;oe@ST#=9th^h0zH^e**zT9?{H(DI&r%d_I^;DN15*FIfWvaPTV z069^7EarW$%y~(amR4PbST-CPZou9I`OJ0~cealG8FrM&3!QG3vvn56Gp#deq`lK~p_t7ufa z({0QHevi<>xi@ll}6NRhUFrdql(t^-7bGZE1=Mx7C~_3*Ny$qbFG8PJkjX z?-o5fpkC0nK%VQpm3_SpL0M%&!#uKjv_KI%@xOGmH*(vYqV^NzJ*vIvD=ad8*Yc@_!}OavbUFkzgZqD!)Vprv2RcYJ02!h+u3 zM|I6lcBEZry~q;eoYSJg4(Z@i222vLWS)OlsV@lE)Y0#`t)|aUQ@TXMA@y79g@Q0B zP1rY;yI`!>yxR4uQX zgRdL(uY|FtI?2-|NNOTA^lz`HE)PsXxD2Q#vmALIUI#o_GT%p2RxrEy+UPo|N#fxX zyz0Sh_cp{eCthSeSACF+cGp}C3dh$LvjTH + + + iw_hub_navigation + 0.1.0 + + The iw_hub_navigation package + + + Isaac Sim + + Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. + NVIDIA CORPORATION and its licensors retain all intellectual property + and proprietary rights in and to this software, related documentation + and any modifications thereto. Any use, reproduction, disclosure or + distribution of this software and related documentation without an express + license agreement from NVIDIA CORPORATION is strictly prohibited. + + https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html + https://forums.developer.nvidia.com/c/omniverse/simulation/69 + + ament_cmake + + launch + launch_ros + + joint_state_publisher + + rviz2 + + nav2_amcl + nav2_bringup + nav2_bt_navigator + nav2_costmap_2d + nav2_core + nav2_dwb_controller + nav2_lifecycle_manager + nav2_map_server + nav2_recoveries + nav2_planner + nav2_msgs + nav2_navfn_planner + nav2_rviz_plugins + nav2_behavior_tree + nav2_util + nav2_voxel_grid + nav2_controller + nav2_waypoint_follower + navigation2 + + + + ament_cmake + + diff --git a/foxy_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml b/foxy_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml new file mode 100644 index 0000000..37e2f25 --- /dev/null +++ b/foxy_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml @@ -0,0 +1,327 @@ +amcl: + ros__parameters: + use_sim_time: True + alpha1: 0.2 + alpha2: 0.2 + alpha3: 0.2 + alpha4: 0.2 + alpha5: 0.2 + base_frame_id: "base_link" + scan_topic: "/front_2d_lidar/scan" + beam_skip_distance: 0.5 + beam_skip_error_threshold: 0.9 + beam_skip_threshold: 0.3 + do_beamskip: false + global_frame_id: "map" + lambda_short: 0.1 + laser_likelihood_max_dist: 2.0 + laser_max_range: 100.0 + laser_min_range: 0.5 + laser_model_type: "likelihood_field" + max_beams: 60 + max_particles: 2000 + min_particles: 500 + odom_frame_id: "odom" + pf_err: 0.05 + pf_z: 0.99 + recovery_alpha_fast: 0.0 + recovery_alpha_slow: 0.0 + resample_interval: 1 + robot_model_type: "differential" + save_pose_rate: 0.5 + sigma_hit: 0.2 + tf_broadcast: true + transform_tolerance: 1.0 + update_min_a: 0.1 + update_min_d: 0.05 + z_hit: 0.5 + z_max: 0.05 + z_rand: 0.5 + z_short: 0.05 + set_initial_pose: True + initial_pose: {x: -6.0, y: 0.0, z: 0.0, yaw: 0.0} + +amcl_map_client: + ros__parameters: + use_sim_time: True + +amcl_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator: + ros__parameters: + use_sim_time: True + global_frame: map + robot_base_frame: base_link + odom_topic: /chassis/odom + default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml" + plugin_lib_names: + - nav2_compute_path_to_pose_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_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 + +bt_navigator_rclcpp_node: + ros__parameters: + use_sim_time: True + +velocity_smoother: + ros__parameters: + smoothing_frequency: 20.0 + scale_velocities: false + feedback: "OPEN_LOOP" + max_velocity: [1.8, 0.0, 1.2] + min_velocity: [-1.8, 0.0, -1.2] + # deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0 + # max_accel: [1.0, 0.0, 1.25] + # max_decel: [-1.0, 0.0, -1.25] + odom_topic: "chassis/odom" + odom_duration: 0.1 + +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 + controller_plugins: ["FollowPath"] + + # 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: 32.0 + PathAlign.forward_point_distance: 0.1 + GoalAlign.scale: 24.0 + GoalAlign.forward_point_distance: 0.1 + PathDist.scale: 32.0 + GoalDist.scale: 24.0 + RotateToGoal.scale: 32.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 + footprint_padding: 0.3 + global_frame: odom + robot_base_frame: base_link + use_sim_time: True + rolling_window: True + width: 10 + height: 10 + resolution: 0.05 + transform_tolerance: 0.3 + footprint: "[ [0.3225, 0.3205], [0.3225, -0.3205], [-1.1175, -0.3205], [-1.1175, 0.3205] ]" + plugins: ["front_rplidar_obstacle_layer", "back_rplidar_obstacle_layer", "inflation_layer"] + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + enabled: True + cost_scaling_factor: 0.3 + inflation_radius: 1.0 + front_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /front_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 5.0 + raytrace_min_range: 0.5 + obstacle_max_range: 5.0 + obstacle_min_range: 0.5 + back_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /back_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 5.0 + raytrace_min_range: 0.5 + obstacle_max_range: 5.0 + obstacle_min_range: 0.5 + 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: + footprint_padding: 0.25 + update_frequency: 1.0 + publish_frequency: 1.0 + global_frame: map + robot_base_frame: base_link + use_sim_time: True + footprint: "[ [0.3225, 0.3205], [0.3225, -0.3205], [-1.1175, -0.3205], [-1.1175, 0.3205] ]" + resolution: 0.05 + plugins: ["static_layer", "front_rplidar_obstacle_layer", "back_rplidar_obstacle_layer", "inflation_layer"] + front_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /front_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + # raytrace_max_range: 10.0 + raytrace_min_range: 0.5 + # obstacle_max_range: 10.0 + obstacle_min_range: 0.5 + back_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /back_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + # raytrace_max_range: 10.0 + raytrace_min_range: 0.5 + # obstacle_max_range: 10.0 + obstacle_min_range: 0.5 + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: True + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 0.3 + inflation_radius: 1.5 + 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_server: + ros__parameters: + use_sim_time: True + yaml_filename: "iw_hub_warehouse_navigation.yaml" + +map_saver: + ros__parameters: + use_sim_time: True + save_map_timeout: 5000 + free_thresh_default: 0.25 + occupied_thresh_default: 0.65 + map_subscribe_transient_local: True + +planner_server: + ros__parameters: + expected_planner_frequency: 10.0 + use_sim_time: True + planner_plugins: ["GridBased"] + GridBased: + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + 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: 5.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: + use_sim_time: True + 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 + diff --git a/foxy_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz b/foxy_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz new file mode 100644 index 0000000..3f34680 --- /dev/null +++ b/foxy_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz @@ -0,0 +1,590 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /RobotModel1 + - /LaserScan1 + Splitter Ratio: 0.5833333134651184 + Tree Height: 597 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: nav2_rviz_plugins/Navigation 2 + Name: Navigation 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: File + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: "" + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 29 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /front_2d_lidar/scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Bumper Hit + Position Transformer: "" + Selectable: true + Size (Pixels): 3 + Size (m): 0.07999999821186066 + Style: Spheres + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /mobile_base/sensors/bumper_pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: true + Enabled: true + Name: Map + Topic: + Depth: 1 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map_updates + Use Timestamp: false + Value: true + - Alpha: 1 + Arrow Length: 0.019999999552965164 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz_default_plugins/PoseArray + Color: 0; 180; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Amcl Particle Swarm + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /particlecloud + Value: true + - Class: rviz_common/Group + Displays: + - Alpha: 0.30000001192092896 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Global Costmap + Topic: + Depth: 1 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/costmap + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/costmap_updates + Use Timestamp: false + Value: true + - Alpha: 0.30000001192092896 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Downsampled Costmap + Topic: + Depth: 1 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /downsampled_costmap + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /downsampled_costmap_updates + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz_default_plugins/Path + Color: 255; 0; 0 + Enabled: true + Head Diameter: 0.019999999552965164 + Head Length: 0.019999999552965164 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: Arrows + Radius: 0.029999999329447746 + Shaft Diameter: 0.004999999888241291 + Shaft Length: 0.019999999552965164 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /plan + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud + Color: 125; 125; 125 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: VoxelGrid + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Boxes + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/voxel_marked_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Class: rviz_default_plugins/Polygon + Color: 25; 255; 0 + Enabled: false + Name: Polygon + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/published_footprint + Value: false + Enabled: true + Name: Global Planner + - Class: rviz_common/Group + Displays: + - Alpha: 0.699999988079071 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Local Costmap + Topic: + Depth: 1 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/costmap + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/costmap_updates + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz_default_plugins/Path + Color: 0; 12; 255 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Local Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_plan + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Trajectories + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /marker + Value: false + - Alpha: 1 + Class: rviz_default_plugins/Polygon + Color: 25; 255; 0 + Enabled: true + Name: Polygon + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/published_footprint + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: VoxelGrid + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/voxel_marked_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Name: Controller + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RealsenseCamera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /intel_realsense_r200_depth/image_raw + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: RealsenseDepthImage + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /intel_realsense_r200_depth/points + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: false + Name: Realsense + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MarkerArray + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /waypoints + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + back_2d_lidar: + Value: true + base_link: + Value: true + chassis: + Value: true + front_2d_lidar: + Value: true + front_stereo_camera: + Value: true + front_stereo_camera_imu: + Value: true + front_stereo_camera_left: + Value: true + front_stereo_camera_left_optical: + Value: true + front_stereo_camera_right: + Value: true + front_stereo_camera_right_optical: + Value: true + map: + Value: true + odom: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + map: + odom: + base_link: + back_2d_lidar: + {} + chassis: + {} + front_2d_lidar: + {} + front_stereo_camera: + {} + front_stereo_camera_imu: + {} + front_stereo_camera_left: + {} + front_stereo_camera_left_optical: + {} + front_stereo_camera_right: + {} + front_stereo_camera_right_optical: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + - Class: nav2_rviz_plugins/GoalTool + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Angle: 1.5700000524520874 + Class: rviz_default_plugins/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Scale: 21.35869598388672 + Target Frame: + Value: TopDownOrtho (rviz_default_plugins) + X: 0 + Y: 1 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 932 + Hide Left Dock: false + Hide Right Dock: false + Navigation 2: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000016a0000034efc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000290000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e0061007600690067006100740069006f006e0020003201000002d1000000b8000000ad00fffffffb0000001e005200650061006c00730065006e0073006500430061006d00650072006100000002c6000000c10000002800ffffff000000010000010f0000034efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b0000034e000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000003840000034e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + RealsenseCamera: + collapsed: false + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1545 + X: 301 + Y: 54 diff --git a/humble_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz b/humble_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz index c904dcd..90cba9a 100644 --- a/humble_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz +++ b/humble_ws/src/isaac_tutorials/rviz2/carter_stereo.rviz @@ -9,9 +9,9 @@ Panels: - /TF1 - /Odometry1/Topic1 - /Left Camera - RGB1 - - /Right Camera - RGB1 + - /Right Camera - RGB1/Topic1 Splitter Ratio: 0.5 - Tree Height: 733 + Tree Height: 718 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -51,42 +51,98 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true + back_fisheye_camera: + Value: true + back_fisheye_camera_optical: + Value: true + back_stereo_camera: + Value: true + back_stereo_camera_imu: + Value: true + back_stereo_camera_left: + Value: true + back_stereo_camera_left_optical: + Value: true + back_stereo_camera_right: + Value: true + back_stereo_camera_right_optical: + Value: true base_link: Value: true - chassis_link: + caster_swivel_left: + Value: true + caster_swivel_right: + Value: true + caster_wheel_left: + Value: true + caster_wheel_right: + Value: true + chassis_imu: Value: true front_2d_lidar: Value: true front_3d_lidar: Value: true + front_fisheye_camera: + Value: true + front_fisheye_camera_optical: + Value: true + front_stereo_camera: + Value: true front_stereo_camera_imu: Value: true + front_stereo_camera_left: + Value: true front_stereo_camera_left_optical: Value: true + front_stereo_camera_right: + Value: true front_stereo_camera_right_optical: Value: true + left_fisheye_camera: + Value: true + left_fisheye_camera_optical: + Value: true + left_stereo_camera: + Value: true left_stereo_camera_imu: Value: true + left_stereo_camera_left: + Value: true left_stereo_camera_left_optical: Value: true + left_stereo_camera_right: + Value: true left_stereo_camera_right_optical: Value: true + nova_carter: + Value: true + nova_carter_caster_frame_base: + Value: true odom: Value: true rear_2d_lidar: Value: true - rear_stereo_camera:imu: + right_fisheye_camera: Value: true - rear_stereo_camera:left_rgb: + right_fisheye_camera_optical: Value: true - rear_stereo_camera:right_rgb: + right_stereo_camera: Value: true right_stereo_camera_imu: Value: true + right_stereo_camera_left: + Value: true right_stereo_camera_left_optical: Value: true + right_stereo_camera_right: + Value: true right_stereo_camera_right_optical: Value: true + wheel_left: + Value: true + wheel_right: + Value: true Marker Scale: 1 Name: TF Show Arrows: true @@ -95,36 +151,91 @@ Visualization Manager: Tree: odom: base_link: - chassis_link: + back_fisheye_camera: + {} + back_fisheye_camera_optical: + {} + back_stereo_camera: + {} + back_stereo_camera_imu: + {} + back_stereo_camera_left: + {} + back_stereo_camera_left_optical: + {} + back_stereo_camera_right: + {} + back_stereo_camera_right_optical: + {} + chassis_imu: {} front_2d_lidar: {} front_3d_lidar: {} + front_fisheye_camera: + {} + front_fisheye_camera_optical: + {} + front_stereo_camera: + {} front_stereo_camera_imu: {} + front_stereo_camera_left: + {} front_stereo_camera_left_optical: {} + front_stereo_camera_right: + {} front_stereo_camera_right_optical: {} + left_fisheye_camera: + {} + left_fisheye_camera_optical: + {} + left_stereo_camera: + {} left_stereo_camera_imu: {} + left_stereo_camera_left: + {} left_stereo_camera_left_optical: {} + left_stereo_camera_right: + {} left_stereo_camera_right_optical: {} + nova_carter: + caster_swivel_left: + {} + caster_swivel_right: + {} + caster_wheel_left: + {} + caster_wheel_right: + {} + nova_carter_caster_frame_base: + {} + wheel_left: + {} + wheel_right: + {} rear_2d_lidar: {} - rear_stereo_camera:imu: + right_fisheye_camera: {} - rear_stereo_camera:left_rgb: + right_fisheye_camera_optical: {} - rear_stereo_camera:right_rgb: + right_stereo_camera: {} right_stereo_camera_imu: {} + right_stereo_camera_left: + {} right_stereo_camera_left_optical: {} + right_stereo_camera_right: + {} right_stereo_camera_right_optical: {} Update Interval: 0 @@ -179,7 +290,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /front_stereo_camera/left/image_raw Value: true - Class: rviz_default_plugins/Image @@ -193,7 +304,7 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /front_stereo_camera/right/image_raw Value: true - Alpha: 1 @@ -225,7 +336,7 @@ Visualization Manager: Durability Policy: Volatile Filter size: 10 History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /front_3d_lidar/lidar_points Use Fixed Frame: true Use rainbow: true @@ -299,12 +410,12 @@ Visualization Manager: Window Geometry: Displays: collapsed: false - Height: 1022 + Height: 1007 Hide Left Dock: false Hide Right Dock: true Left Camera - RGB: collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000001f7000003a4fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003a4000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002800520069006700680074002000430061006d0065007200610020002d002000440065007000740068020000128b00000218000002390000017ffb00000026004c006500660074002000430061006d0065007200610020002d002000440065007000740068020000102e000002180000023c00000181fb00000022004c006500660074002000430061006d0065007200610020002d002000520047004203000010200000020c000001f30000011efb0000002400520069006700680074002000430061006d0065007200610020002d002000520047004203000012530000020d000001f30000011efb0000000a0049006d006100670065030000236c0000040e0000023e0000017e000000010000015f000003a4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000003a4000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004e5000003a400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001f700000395fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000395000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002800520069006700680074002000430061006d0065007200610020002d002000440065007000740068020000128b00000218000002390000017ffb00000026004c006500660074002000430061006d0065007200610020002d002000440065007000740068020000102e000002180000023c00000181fb00000022004c006500660074002000430061006d0065007200610020002d0020005200470042030000080a0000018d000001f30000011efb0000002400520069006700680074002000430061006d0065007200610020002d002000520047004203000008320000039d000001f30000011efb0000000a0049006d006100670065030000236c0000040e0000023e0000017e000000010000015f000003a4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000003a4000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000006950000039500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Right Camera - RGB: collapsed: false Selection: @@ -313,6 +424,6 @@ Window Geometry: collapsed: false Views: collapsed: true - Width: 1762 - X: 3585 - Y: 352 + Width: 2194 + X: 458 + Y: 217 diff --git a/humble_ws/src/isaacsim/launch/run_isaacsim.launch.py b/humble_ws/src/isaacsim/launch/run_isaacsim.launch.py index 1802953..e7c2a49 100644 --- a/humble_ws/src/isaacsim/launch/run_isaacsim.launch.py +++ b/humble_ws/src/isaacsim/launch/run_isaacsim.launch.py @@ -16,7 +16,7 @@ # Declare all launch arguments corresponding to the bash script options launch_args = [ - DeclareLaunchArgument('version', default_value='4.1.0', description='Specify the version of Isaac Sim to use. Isaac Sim will be run from default install root folder for the specified version. Leave empty to use latest version of Isaac Sim.'), + DeclareLaunchArgument('version', default_value='4.2.0', description='Specify the version of Isaac Sim to use. Isaac Sim will be run from default install root folder for the specified version. Leave empty to use latest version of Isaac Sim.'), DeclareLaunchArgument('install_path', default_value='', description='If Isaac Sim is insalled in a non-default location, provide a specific path to Isaac Sim installation root folder. (If defined, "version" parameter will be ignored)'), diff --git a/humble_ws/src/isaacsim/scripts/run_isaacsim.py b/humble_ws/src/isaacsim/scripts/run_isaacsim.py index ac97425..2111cfe 100755 --- a/humble_ws/src/isaacsim/scripts/run_isaacsim.py +++ b/humble_ws/src/isaacsim/scripts/run_isaacsim.py @@ -20,7 +20,7 @@ # Default values defaults = { - "isaac_sim_version": "4.1.0", + "isaac_sim_version": "4.2.0", "isaac_sim_path": "", "use_internal_libs": False, "dds_type": "fastdds", @@ -106,7 +106,7 @@ def execute_launch(self): # If custom Isaac Sim Installation folder not given, use the default path using version number provided. home_var = "USERPROFILE" if sys.platform == "win32" else "HOME" home_path = os.getenv(home_var) - if version_ge(args.version, "4.1.0") and not version_gt(args.version, "2021.2.0"): + if version_ge(args.version, "4.2.0") and not version_gt(args.version, "2021.2.0"): if sys.platform == "win32": filepath_root = os.path.join(home_path, "AppData", "Local", "ov", "pkg", f"isaac-sim-{args.version}") else: diff --git a/humble_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py b/humble_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py index 556c01e..b6e52c1 100644 --- a/humble_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py +++ b/humble_ws/src/navigation/carter_navigation/launch/carter_navigation_isaacsim.launch.py @@ -63,7 +63,7 @@ def execute_second_node_if_condition_met(event, second_node_action): return LaunchDescription( [ # Declaring the Isaac Sim scene path. 'gui' launch argument is already used withing run_isaac_sim.launch.py - DeclareLaunchArgument("gui", default_value='omniverse://localhost/NVIDIA/Assets/Isaac/4.1/Isaac/Samples/ROS2/Scenario/carter_warehouse_navigation.usd', description="Path to isaac sim scene"), + DeclareLaunchArgument("gui", default_value='omniverse://localhost/NVIDIA/Assets/Isaac/4.2/Isaac/Samples/ROS2/Scenario/carter_warehouse_navigation.usd', description="Path to isaac sim scene"), # Include Isaac Sim launch file from isaacsim package with given launch parameters. IncludeLaunchDescription( @@ -73,7 +73,7 @@ def execute_second_node_if_condition_met(event, second_node_action): ] ), launch_arguments={ - 'version': '4.1.0', + 'version': '4.2.0', 'play_sim_on_start': 'true', }.items(), ), diff --git a/humble_ws/src/navigation/carter_navigation/rviz2/carter_navigation.rviz b/humble_ws/src/navigation/carter_navigation/rviz2/carter_navigation.rviz index 79c3b79..a38223b 100644 --- a/humble_ws/src/navigation/carter_navigation/rviz2/carter_navigation.rviz +++ b/humble_ws/src/navigation/carter_navigation/rviz2/carter_navigation.rviz @@ -5,13 +5,15 @@ Panels: Property Tree Widget: Expanded: - /Global Options1 - - /RobotModel1 - /TF1/Frames1 - /TF1/Tree1 + - /LaserScan1/Status1 - /Controller1 - /Controller1/Local Costmap1 + - /Image1/Status1 + - /Image1/Topic1 Splitter Ratio: 0.5833333134651184 - Tree Height: 203 + Tree Height: 199 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -78,44 +80,100 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: false - back_2d_lidar: + back_fisheye_camera: + Value: true + back_fisheye_camera_optical: + Value: true + back_stereo_camera: + Value: true + back_stereo_camera_imu: + Value: true + back_stereo_camera_left: + Value: true + back_stereo_camera_left_optical: + Value: true + back_stereo_camera_right: + Value: true + back_stereo_camera_right_optical: Value: true base_link: Value: true - chassis_link: + caster_swivel_left: + Value: true + caster_swivel_right: + Value: true + caster_wheel_left: + Value: true + caster_wheel_right: + Value: true + chassis_imu: Value: true front_2d_lidar: Value: true front_3d_lidar: Value: true + front_fisheye_camera: + Value: true + front_fisheye_camera_optical: + Value: true + front_stereo_camera: + Value: true front_stereo_camera_imu: Value: true + front_stereo_camera_left: + Value: true front_stereo_camera_left_optical: Value: true + front_stereo_camera_right: + Value: true front_stereo_camera_right_optical: Value: true + left_fisheye_camera: + Value: true + left_fisheye_camera_optical: + Value: true + left_stereo_camera: + Value: true left_stereo_camera_imu: Value: true + left_stereo_camera_left: + Value: true left_stereo_camera_left_optical: Value: true + left_stereo_camera_right: + Value: true left_stereo_camera_right_optical: Value: true map: Value: true + nova_carter: + Value: true + nova_carter_caster_frame_base: + Value: true odom: Value: true - rear_stereo_camera:imu: + rear_2d_lidar: + Value: true + right_fisheye_camera: Value: true - rear_stereo_camera:left_rgb: + right_fisheye_camera_optical: Value: true - rear_stereo_camera:right_rgb: + right_stereo_camera: Value: true right_stereo_camera_imu: Value: true + right_stereo_camera_left: + Value: true right_stereo_camera_left_optical: Value: true + right_stereo_camera_right: + Value: true right_stereo_camera_right_optical: Value: true + wheel_left: + Value: true + wheel_right: + Value: true Marker Scale: 1 Name: TF Show Arrows: true @@ -125,36 +183,91 @@ Visualization Manager: map: odom: base_link: - back_2d_lidar: + back_fisheye_camera: + {} + back_fisheye_camera_optical: + {} + back_stereo_camera: + {} + back_stereo_camera_imu: + {} + back_stereo_camera_left: + {} + back_stereo_camera_left_optical: + {} + back_stereo_camera_right: {} - chassis_link: + back_stereo_camera_right_optical: + {} + chassis_imu: {} front_2d_lidar: {} front_3d_lidar: {} + front_fisheye_camera: + {} + front_fisheye_camera_optical: + {} + front_stereo_camera: + {} front_stereo_camera_imu: {} + front_stereo_camera_left: + {} front_stereo_camera_left_optical: {} + front_stereo_camera_right: + {} front_stereo_camera_right_optical: {} + left_fisheye_camera: + {} + left_fisheye_camera_optical: + {} + left_stereo_camera: + {} left_stereo_camera_imu: {} + left_stereo_camera_left: + {} left_stereo_camera_left_optical: {} + left_stereo_camera_right: + {} left_stereo_camera_right_optical: {} - rear_stereo_camera:imu: + nova_carter: + caster_swivel_left: + {} + caster_swivel_right: + {} + caster_wheel_left: + {} + caster_wheel_right: + {} + nova_carter_caster_frame_base: + {} + wheel_left: + {} + wheel_right: + {} + rear_2d_lidar: + {} + right_fisheye_camera: {} - rear_stereo_camera:left_rgb: + right_fisheye_camera_optical: {} - rear_stereo_camera:right_rgb: + right_stereo_camera: {} right_stereo_camera_imu: {} + right_stereo_camera_left: + {} right_stereo_camera_left_optical: {} + right_stereo_camera_right: + {} right_stereo_camera_right_optical: {} Update Interval: 0 @@ -601,7 +714,7 @@ Visualization Manager: Use rainbow: true Value: true - Class: rviz_default_plugins/Image - Enabled: false + Enabled: true Max Value: 1 Median window: 5 Min Value: 0 @@ -611,9 +724,9 @@ Visualization Manager: Depth: 5 Durability Policy: Volatile History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /front_stereo_camera/left/image_raw - Value: false + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -682,7 +795,7 @@ Window Geometry: collapsed: false Navigation 2: collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000016a0000028afc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afc0000003b00000106000000c700fffffffa000000010100000002fb0000000a0049006d0061006700650200000526000002090000016a000000e7fb000000100044006900730070006c00610079007301000000000000016a0000015600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e0061007600690067006100740069006f006e0020003201000001470000017e0000012300fffffffb0000001e005200650061006c00730065006e0073006500430061006d00650072006100000002c6000000c10000002800ffffff000000010000010f0000028afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b0000028a000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b2000000000000000000000002000004ba00000094fc0100000002fb0000000a0049006d006100670065030000037d000002170000016c00000104fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000034a0000028a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd00000004000000000000016a00000286fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afc0000003d00000104000000c900fffffffa000000010100000002fb0000000a0049006d0061006700650300000396000002090000016a000000e7fb000000100044006900730070006c00610079007301000000000000016a0000015600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e0061007600690067006100740069006f006e0020003201000001470000017c0000012600fffffffb0000001e005200650061006c00730065006e0073006500430061006d00650072006100000002c6000000c10000002800ffffff000000010000010f0000028afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b0000028a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b2000000000000000000000002000004ba00000094fc0100000002fb0000000a0049006d006100670065030000037d000002170000016c00000104fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000034a0000028600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 RealsenseCamera: collapsed: false Selection: @@ -692,5 +805,5 @@ Window Geometry: Views: collapsed: true Width: 1210 - X: 470 - Y: 28 + X: 70 + Y: 27 diff --git a/humble_ws/src/navigation/iw_hub_navigation/CMakeLists.txt b/humble_ws/src/navigation/iw_hub_navigation/CMakeLists.txt new file mode 100644 index 0000000..dc12c87 --- /dev/null +++ b/humble_ws/src/navigation/iw_hub_navigation/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 3.5) +project(iw_hub_navigation) + +find_package(ament_cmake REQUIRED) + +install(DIRECTORY + launch + params + maps + rviz2 + DESTINATION share/${PROJECT_NAME}) + +ament_package() diff --git a/humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py b/humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py new file mode 100644 index 0000000..a24103d --- /dev/null +++ b/humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation.launch.py @@ -0,0 +1,58 @@ +## Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. +## NVIDIA CORPORATION and its licensors retain all intellectual property +## and proprietary rights in and to this software, related documentation +## and any modifications thereto. Any use, reproduction, disclosure or +## distribution of this software and related documentation without an express +## license agreement from NVIDIA CORPORATION is strictly prohibited. + +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + + use_sim_time = LaunchConfiguration("use_sim_time", default="True") + + map_dir = LaunchConfiguration( + "map", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "maps", "iw_hub_warehouse_navigation.yaml" + ), + ) + + param_dir = LaunchConfiguration( + "params_file", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "params", "iw_hub_navigation_params.yaml" + ), + ) + + nav2_bringup_launch_dir = os.path.join(get_package_share_directory("nav2_bringup"), "launch") + + rviz_config_dir = os.path.join(get_package_share_directory("iw_hub_navigation"), "rviz2", "iw_hub_navigation.rviz") + + return LaunchDescription( + [ + DeclareLaunchArgument("map", default_value=map_dir, description="Full path to map file to load"), + DeclareLaunchArgument( + "params_file", default_value=param_dir, description="Full path to param file to load" + ), + DeclareLaunchArgument( + "use_sim_time", default_value="true", description="Use simulation (Omniverse Isaac Sim) clock if true" + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(nav2_bringup_launch_dir, "rviz_launch.py")), + launch_arguments={"namespace": "", "use_namespace": "False", "rviz_config": rviz_config_dir}.items(), + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource([nav2_bringup_launch_dir, "/bringup_launch.py"]), + launch_arguments={"map": map_dir, "use_sim_time": use_sim_time, "params_file": param_dir}.items(), + ), + ] + ) diff --git a/humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py b/humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py new file mode 100644 index 0000000..0ee14d3 --- /dev/null +++ b/humble_ws/src/navigation/iw_hub_navigation/launch/iw_hub_navigation_isaacsim.launch.py @@ -0,0 +1,103 @@ +## Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. +## NVIDIA CORPORATION and its licensors retain all intellectual property +## and proprietary rights in and to this software, related documentation +## and any modifications thereto. Any use, reproduction, disclosure or +## distribution of this software and related documentation without an express +## license agreement from NVIDIA CORPORATION is strictly prohibited. + +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node +from launch.actions import RegisterEventHandler, ExecuteProcess +from launch.event_handlers import OnProcessStart, OnProcessIO +from launch.substitutions import FindExecutable + +def generate_launch_description(): + + use_sim_time = LaunchConfiguration("use_sim_time", default="True") + + map_dir = LaunchConfiguration( + "map", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "maps", "iw_hub_warehouse_navigation.yaml" + ), + ) + + param_dir = LaunchConfiguration( + "params_file", + default=os.path.join( + get_package_share_directory("iw_hub_navigation"), "params", "iw_hub_navigation_params.yaml" + ), + ) + + + nav2_bringup_launch_dir = os.path.join(get_package_share_directory("nav2_bringup"), "launch") + + rviz_config_dir = os.path.join(get_package_share_directory("iw_hub_navigation"), "rviz2", "iw_hub_navigation.rviz") + + ld_automatic_goal = IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory("isaac_ros_navigation_goal"), "launch", "isaac_ros_navigation_goal.launch.py" + ), + ] + ), + ) + + + + def execute_second_node_if_condition_met(event, second_node_action): + output = event.text.decode().strip() + # Look for fully loaded message from Isaac Sim. Only applicable in Gui mode. + if "Stage loaded and simulation is playing." in output: + # Log a message indicating the condition has been met + print("Condition met, launching the second node.") + + return second_node_action + + + return LaunchDescription( + [ + # Declaring the Isaac Sim scene path. 'gui' launch argument is already used withing run_isaac_sim.launch.py + DeclareLaunchArgument("gui", default_value='omniverse://localhost/NVIDIA/Assets/Isaac/4.2/Isaac/Samples/ROS2/Scenario/iw_hub_warehouse_navigation.usd', description="Path to isaac sim scene"), + + # Include Isaac Sim launch file from isaacsim package with given launch parameters. + IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory("isaacsim"), "launch", "run_isaacsim.launch.py" + ), + ] + ), + launch_arguments={ + 'version': '4.2.0', + 'play_sim_on_start': 'true', + }.items(), + ), + + DeclareLaunchArgument("map", default_value=map_dir, description="Full path to map file to load"), + DeclareLaunchArgument( + "params_file", default_value=param_dir, description="Full path to param file to load" + ), + DeclareLaunchArgument( + "use_sim_time", default_value="true", description="Use simulation (Omniverse Isaac Sim) clock if true" + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(nav2_bringup_launch_dir, "rviz_launch.py")), + launch_arguments={"namespace": "", "use_namespace": "False", "rviz_config": rviz_config_dir}.items(), + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource([nav2_bringup_launch_dir, "/bringup_launch.py"]), + launch_arguments={"map": map_dir, "use_sim_time": use_sim_time, "params_file": param_dir}.items(), + ), + # Launch automatic goal generator node when Isaac Sim has finished loading. + RegisterEventHandler( + OnProcessIO( + on_stdout=lambda event: execute_second_node_if_condition_met(event, ld_automatic_goal) + ) + ), + ] + ) diff --git a/humble_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.png b/humble_ws/src/navigation/iw_hub_navigation/maps/iw_hub_warehouse_navigation.png new file mode 100644 index 0000000000000000000000000000000000000000..9f477db1a5c3798348401bb3ad407d171ce6cdb1 GIT binary patch literal 5023 zcmeHLdr(tX9zHkW6%3(-vVsQiQBW3^1cE#SiK0R&_*iF4i}Hw%h*W`;fCPC3R1ljH zQAZM`u`FArTPesxUJ|^31zlnSixMFSB9Nd!jb0Woy!L>PsWa_PcV_GCv}W>0a_5|T z?m6G@d;D(Z_N_h!`b+cy00zDvZrT9=js^hUUQY*J(cS3={}}K0-L&B^+}zRo5mA=| zmaPA?>0rvrWH&7D*_TcwdsU}y@9w|)w~s16+nN6usW7Apb6B0$fOmS1-va=zmrMie zPw@~CtwjW3&Aa_*{F!rMO|b<@1ST%>+{LD6W|-eL_PTIiqGc z*>qvNXfqMS5d>Gn+r}DjynMDX_2rr8oaR>hP}fy&Fy#3JroKd@pG?l^vsnc!SlYi8 z6eKOBhw?oWgXPy4Wf6_ehCDDIK|DMd@rFGWhg7Yp48Q3YsU`1>`DJoW{YR zzG>9Se42db?qc3VS;WPDMx6OtCICgR%aUYH%j(V~q16&>WKtH~h*x&pAF#;Ab31yfmm*Nn{{h`ENuEK>_w``ES{dL|&*QC7z8%j(NH4M4KrtAcm)N4fh* zfO}^*ZvTZ%M4%RI)FuLSg z!1_fpOfqw8G45U#FO$nEcO7~bnMmMyA{;iUTum9ba$QU;>Kb_)ukzF&-U z)kTc^vOfcpmPn&Z-5MM_2A3XHILToC4cOG{!K_}2k{2|a9&sM^YerZc}(Zf5-c zsJ}yr6j(!P)FS*=r17l2AYSAXg#&CLRv%UJwbL%1rZ(Ox)aOziov$dQDUNR{pb-)y^`0sp{KmYBfc< zjz+2hiLs;WXtXW5RmZe|de<9<<%mGRSek_J!Y_D1?AY1*rcuhl7x;GW`Xk(K!6QH| zO*mJhvXeMM(9NvMaQ!+V(guS^^RS=uNBz&9=nGmXh?f(5;WKY|W0hZUV(*5$ktlq% zB_6VT7ev(L!GU}he~nXqJi>)1uJrGSH5U^occ2w;Z(KIKsi+W-T{pZW43iGr#cJ(Z z{N|=&tOA%75uEKxrv+Hdtc+-j50j-gUfoIuFfXi_Kx@0?2dnCQx9^AScX=B9g~|Vn zx2nAZ8O6gIl??L;oe@ST#=9th^h0zH^e**zT9?{H(DI&r%d_I^;DN15*FIfWvaPTV z069^7EarW$%y~(amR4PbST-CPZou9I`OJ0~cealG8FrM&3!QG3vvn56Gp#deq`lK~p_t7ufa z({0QHevi<>xi@ll}6NRhUFrdql(t^-7bGZE1=Mx7C~_3*Ny$qbFG8PJkjX z?-o5fpkC0nK%VQpm3_SpL0M%&!#uKjv_KI%@xOGmH*(vYqV^NzJ*vIvD=ad8*Yc@_!}OavbUFkzgZqD!)Vprv2RcYJ02!h+u3 zM|I6lcBEZry~q;eoYSJg4(Z@i222vLWS)OlsV@lE)Y0#`t)|aUQ@TXMA@y79g@Q0B zP1rY;yI`!>yxR4uQX zgRdL(uY|FtI?2-|NNOTA^lz`HE)PsXxD2Q#vmALIUI#o_GT%p2RxrEy+UPo|N#fxX zyz0Sh_cp{eCthSeSACF+cGp}C3dh$LvjTH + + + iw_hub_navigation + 0.1.0 + + The iw_hub_navigation package + + + Isaac Sim + + Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. + NVIDIA CORPORATION and its licensors retain all intellectual property + and proprietary rights in and to this software, related documentation + and any modifications thereto. Any use, reproduction, disclosure or + distribution of this software and related documentation without an express + license agreement from NVIDIA CORPORATION is strictly prohibited. + + https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html + https://forums.developer.nvidia.com/c/omniverse/simulation/69 + + ament_cmake + + launch + launch_ros + + joint_state_publisher + + rviz2 + + navigation2 + nav2_amcl + nav2_bringup + nav2_bt_navigator + nav2_costmap_2d + nav2_core + nav2_dwb_controller + nav2_lifecycle_manager + nav2_map_server + nav2_behaviors + nav2_planner + nav2_msgs + nav2_navfn_planner + nav2_rviz_plugins + nav2_behavior_tree + nav2_util + nav2_voxel_grid + nav2_controller + nav2_waypoint_follower + pointcloud_to_laserscan + + + + ament_cmake + + diff --git a/humble_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml b/humble_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml new file mode 100644 index 0000000..37bb6de --- /dev/null +++ b/humble_ws/src/navigation/iw_hub_navigation/params/iw_hub_navigation_params.yaml @@ -0,0 +1,384 @@ +amcl: + ros__parameters: + use_sim_time: True + alpha1: 0.2 + alpha2: 0.2 + alpha3: 0.2 + alpha4: 0.2 + alpha5: 0.2 + base_frame_id: "base_link" + beam_skip_distance: 0.5 + beam_skip_error_threshold: 0.9 + beam_skip_threshold: 0.3 + do_beamskip: false + global_frame_id: "map" + lambda_short: 0.1 + laser_likelihood_max_dist: 2.0 + laser_max_range: 100.0 + laser_min_range: 0.5 + laser_model_type: "likelihood_field" + max_beams: 60 + max_particles: 2000 + min_particles: 500 + odom_frame_id: "odom" + pf_err: 0.05 + pf_z: 0.99 + recovery_alpha_fast: 0.0 + recovery_alpha_slow: 0.0 + resample_interval: 1 + robot_model_type: "nav2_amcl::DifferentialMotionModel" + save_pose_rate: 0.5 + sigma_hit: 0.2 + tf_broadcast: true + transform_tolerance: 1.0 + update_min_a: 0.1 + update_min_d: 0.05 + z_hit: 0.5 + z_max: 0.05 + z_rand: 0.5 + z_short: 0.05 + scan_topic: "/front_2d_lidar/scan" + map_topic: map + set_initial_pose: true + always_reset_initial_pose: false + first_map_only: false + initial_pose: + x: -6.0 + y: 0.0 + z: 0.0 + yaw: 0.0 + +amcl_map_client: + ros__parameters: + use_sim_time: True + +amcl_rclcpp_node: + ros__parameters: + use_sim_time: True +bt_navigator: + ros__parameters: + use_sim_time: True + global_frame: map + robot_base_frame: base_link + odom_topic: /chassis/odom + bt_loop_duration: 20 + default_server_timeout: 40 + # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: + # 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. + plugin_lib_names: + - nav2_compute_path_to_pose_action_bt_node + - nav2_compute_path_through_poses_action_bt_node + - nav2_smooth_path_action_bt_node + - nav2_follow_path_action_bt_node + - nav2_spin_action_bt_node + - nav2_wait_action_bt_node + - nav2_back_up_action_bt_node + - nav2_drive_on_heading_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_globally_updated_goal_condition_bt_node + - nav2_is_path_valid_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_truncate_path_local_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_path_expiring_timer_condition + - 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 + - nav2_controller_cancel_bt_node + - nav2_path_longer_on_approach_bt_node + - nav2_wait_cancel_bt_node + - nav2_spin_cancel_bt_node + - nav2_back_up_cancel_bt_node + - nav2_drive_on_heading_cancel_bt_node + +bt_navigator_rclcpp_node: + ros__parameters: + use_sim_time: True + +velocity_smoother: + ros__parameters: + smoothing_frequency: 20.0 + scale_velocities: false + feedback: "OPEN_LOOP" + max_velocity: [1.8, 0.0, 1.2] + min_velocity: [-1.8, 0.0, -1.2] + velocity_timeout: 1.0 + odom_topic: "chassis/odom" + odom_duration: 0.1 + +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_plugin: ["stopped_goal_checker"] + controller_plugins: ["FollowPath"] + + # Progress checker parameters + progress_checker: + plugin: "nav2_controller::SimpleProgressChecker" + required_movement_radius: 0.5 + movement_time_allowance: 10.0 + # Goal checker parameters + stopped_goal_checker: + plugin: "nav2_controller::StoppedGoalChecker" + xy_goal_tolerance: 0.25 + yaw_goal_tolerance: 0.25 + stateful: True + # 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: 32.0 + PathAlign.forward_point_distance: 0.1 + GoalAlign.scale: 24.0 + GoalAlign.forward_point_distance: 0.1 + PathDist.scale: 32.0 + GoalDist.scale: 24.0 + RotateToGoal.scale: 32.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 + footprint_padding: 0.3 + global_frame: odom + robot_base_frame: base_link + use_sim_time: True + rolling_window: True + width: 10 + height: 10 + resolution: 0.05 + transform_tolerance: 0.3 + footprint: "[ [0.3225, 0.3205], [0.3225, -0.3205], [-1.1175, -0.3205], [-1.1175, 0.3205] ]" + plugins: ["front_rplidar_obstacle_layer", "back_rplidar_obstacle_layer", "inflation_layer"] + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + enabled: True + cost_scaling_factor: 0.3 + inflation_radius: 1.0 + front_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /front_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 5.0 + raytrace_min_range: 0.5 + obstacle_max_range: 5.0 + obstacle_min_range: 0.5 + back_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /back_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 5.0 + raytrace_min_range: 0.5 + obstacle_max_range: 5.0 + obstacle_min_range: 0.5 + 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: + footprint_padding: 0.25 + update_frequency: 1.0 + publish_frequency: 1.0 + global_frame: map + robot_base_frame: base_link + use_sim_time: True + footprint: "[ [0.3225, 0.3205], [0.3225, -0.3205], [-1.1175, -0.3205], [-1.1175, 0.3205] ]" + resolution: 0.05 + plugins: ["static_layer", "front_rplidar_obstacle_layer", "back_rplidar_obstacle_layer", "inflation_layer"] + front_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /front_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + # raytrace_max_range: 10.0 + raytrace_min_range: 0.5 + # obstacle_max_range: 10.0 + obstacle_min_range: 0.5 + back_rplidar_obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /back_2d_lidar/scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + # raytrace_max_range: 10.0 + raytrace_min_range: 0.5 + # obstacle_max_range: 10.0 + obstacle_min_range: 0.5 + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: True + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 0.3 + inflation_radius: 1.5 + 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_server: + ros__parameters: + use_sim_time: True + yaml_filename: "iw_hub_warehouse_navigation.yaml" + +map_saver: + ros__parameters: + use_sim_time: True + save_map_timeout: 5000 + free_thresh_default: 0.25 + occupied_thresh_default: 0.65 + map_subscribe_transient_local: True + +planner_server: + ros__parameters: + expected_planner_frequency: 10.0 + use_sim_time: True + planner_plugins: ["GridBased"] + GridBased: + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + +planner_server_rclcpp_node: + ros__parameters: + use_sim_time: True + +smoother_server: + ros__parameters: + use_sim_time: True + smoother_plugins: ["simple_smoother"] + simple_smoother: + plugin: "nav2_smoother::SimpleSmoother" + tolerance: 1.0e-10 + max_its: 1000 + do_refinement: True + +behavior_server: + ros__parameters: + costmap_topic: local_costmap/costmap_raw + footprint_topic: local_costmap/published_footprint + cycle_frequency: 5.0 + behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] + spin: + plugin: "nav2_behaviors/Spin" + backup: + plugin: "nav2_behaviors/BackUp" + drive_on_heading: + plugin: "nav2_behaviors/DriveOnHeading" + wait: + plugin: "nav2_behaviors/Wait" + global_frame: odom + robot_base_frame: base_link + transform_tolerance: 0.2 + 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: + use_sim_time: True + 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 + diff --git a/humble_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz b/humble_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz new file mode 100644 index 0000000..80412f0 --- /dev/null +++ b/humble_ws/src/navigation/iw_hub_navigation/rviz2/iw_hub_navigation.rviz @@ -0,0 +1,667 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /RobotModel1 + - /LaserScan1 + - /Controller1 + - /Controller1/Local Costmap1 + Splitter Ratio: 0.5833333134651184 + Tree Height: 228 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: nav2_rviz_plugins/Navigation 2 + Name: Navigation 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: File + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: "" + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 30 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /front_2d_lidar/scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Bumper Hit + Position Transformer: "" + Selectable: true + Size (Pixels): 3 + Size (m): 0.07999999821186066 + Style: Spheres + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /mobile_base/sensors/bumper_pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: true + Enabled: true + Name: Map + Topic: + Depth: 1 + Durability Policy: Transient Local + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map_updates + Use Timestamp: false + Value: true + - Alpha: 1 + Arrow Length: 0.019999999552965164 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz_default_plugins/PoseArray + Color: 0; 180; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Amcl Particle Swarm + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /particlecloud + Value: true + - Class: rviz_common/Group + Displays: + - Alpha: 0.30000001192092896 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Global Costmap + Topic: + Depth: 1 + Durability Policy: Transient Local + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/costmap + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/costmap_updates + Use Timestamp: false + Value: true + - Alpha: 0.30000001192092896 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Downsampled Costmap + Topic: + Depth: 1 + Durability Policy: Transient Local + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /downsampled_costmap + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /downsampled_costmap_updates + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz_default_plugins/Path + Color: 255; 0; 0 + Enabled: true + Head Diameter: 0.019999999552965164 + Head Length: 0.019999999552965164 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: Arrows + Radius: 0.029999999329447746 + Shaft Diameter: 0.004999999888241291 + Shaft Length: 0.019999999552965164 + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /plan + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud + Color: 125; 125; 125 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: VoxelGrid + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Boxes + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/voxel_marked_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Class: rviz_default_plugins/Polygon + Color: 25; 255; 0 + Enabled: false + Name: Polygon + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/published_footprint + Value: false + Enabled: true + Name: Global Planner + - Class: rviz_common/Group + Displays: + - Alpha: 0.699999988079071 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Local Costmap + Topic: + Depth: 1 + Durability Policy: Transient Local + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/costmap + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/costmap_updates + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz_default_plugins/Path + Color: 0; 12; 255 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Local Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_plan + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: Trajectories + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /marker + Value: false + - Alpha: 1 + Class: rviz_default_plugins/Polygon + Color: 25; 255; 0 + Enabled: true + Name: Polygon + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/published_footprint + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: VoxelGrid + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/voxel_marked_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Name: Controller + - Class: rviz_common/Group + Displays: + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RealsenseCamera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /intel_realsense_r200_depth/image_raw + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: RealsenseDepthImage + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /intel_realsense_r200_depth/points + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: false + Name: Realsense + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MarkerArray + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /waypoints + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 5.605445384979248 + Min Value: 0.0022323131561279297 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /front_3d_lidar/lidar_points + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /front_stereo_camera/left/image_raw + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + back_2d_lidar: + Value: true + base_link: + Value: true + chassis: + Value: true + front_2d_lidar: + Value: true + front_stereo_camera: + Value: true + front_stereo_camera_imu: + Value: true + front_stereo_camera_left: + Value: true + front_stereo_camera_left_optical: + Value: true + front_stereo_camera_right: + Value: true + front_stereo_camera_right_optical: + Value: true + map: + Value: true + odom: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + map: + odom: + base_link: + back_2d_lidar: + {} + chassis: + {} + front_2d_lidar: + {} + front_stereo_camera: + {} + front_stereo_camera_imu: + {} + front_stereo_camera_left: + {} + front_stereo_camera_left_optical: + {} + front_stereo_camera_right: + {} + front_stereo_camera_right_optical: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + - Class: nav2_rviz_plugins/GoalTool + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 33.447593688964844 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.8421784043312073 + Y: 1.7431563138961792 + Z: 1.6975823640823364 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.2897965908050537 + Target Frame: + Value: Orbit (rviz_default_plugins) + Yaw: 6.277405261993408 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 840 + Hide Left Dock: false + Hide Right Dock: true + Image: + collapsed: false + Navigation 2: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000016a000002eefc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000121000000c900fffffffb0000000a0049006d00610067006503000004b50000029600000174000000fafb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e0061007600690067006100740069006f006e002000320100000164000001c70000012600fffffffb0000001e005200650061006c00730065006e0073006500430061006d00650072006100000002c6000000c10000002800ffffff000000010000010f0000037cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d0000037c000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b2000000000000000000000002000004ba00000094fc0100000002fb0000000a0049006d006100670065030000037d000002170000016c00000104fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000387000002ee00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + RealsenseCamera: + collapsed: false + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1271 + X: 976 + Y: 60 diff --git a/noetic_ws/src/isaac_tutorials/rviz/camera_lidar.rviz b/noetic_ws/src/isaac_tutorials/rviz/camera_lidar.rviz index e159ff0..c44b900 100644 --- a/noetic_ws/src/isaac_tutorials/rviz/camera_lidar.rviz +++ b/noetic_ws/src/isaac_tutorials/rviz/camera_lidar.rviz @@ -1,15 +1,14 @@ Panels: - Class: rviz/Displays - Help Height: 138 + Help Height: 0 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 - - /Camera1_RGB1 - - /Camera1_RGB1/Status1 + - /LaserScan1 Splitter Ratio: 0.5 - Tree Height: 591 + Tree Height: 605 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -76,13 +75,13 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.10000000149011612 Style: Flat Squares - Topic: /laser_scan + Topic: /scan Unreliable: false - Use Fixed Frame: true + Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz/Image - Enabled: false + Enabled: true Image Topic: /camera_1/depth/image_rect_raw Max Value: 1 Median window: 5 @@ -92,7 +91,7 @@ Visualization Manager: Queue Size: 2 Transport Hint: raw Unreliable: false - Value: false + Value: true - Class: rviz/Image Enabled: false Image Topic: /camera_2/depth/image_rect_raw @@ -105,6 +104,30 @@ Visualization Manager: Transport Hint: raw Unreliable: false Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /camera_1/rgb/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Camera1_RGB + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera_2/rgb/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Camera_2_RGB + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true - Class: rviz/TF Enabled: true Filter (blacklist): "" @@ -112,6 +135,8 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true + Camera_1: + Value: true Camera_2: Value: true Lidar: @@ -122,8 +147,6 @@ Visualization Manager: Value: true base_scan: Value: true - camera_1: - Value: true caster_back_link: Value: true imu_link: @@ -134,8 +157,6 @@ Visualization Manager: Value: true wheel_right_link: Value: true - world: - Value: true Marker Alpha: 1 Marker Scale: 1 Name: TF @@ -144,13 +165,13 @@ Visualization Manager: Show Names: true Tree: odom: - {} - world: - Camera_2: - {} - Lidar: - {} base_link: + Camera_1: + {} + Camera_2: + {} + Lidar: + {} base_footprint: {} base_scan: @@ -163,39 +184,41 @@ Visualization Manager: {} wheel_right_link: {} - camera_1: - {} Update Interval: 0 Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /camera_1/rgb/image_raw - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Camera1_RGB - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 Enabled: true - Image Topic: /camera_2/rgb/image_raw - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Camera_2_RGB - Normalize Range: true - Queue Size: 2 - Transport Hint: raw + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /point_cloud Unreliable: false + Use Fixed Frame: true + Use rainbow: true Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true - Fixed Frame: world + Fixed Frame: odom Frame Rate: 30 Name: root Tools: @@ -219,7 +242,7 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 17.770366668701172 + Distance: 13.975852966308594 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -227,17 +250,17 @@ Visualization Manager: Value: false Field of View: 0.7853981852531433 Focal Point: - X: -0.006776329129934311 - Y: -0.7690384984016418 - Z: 0.5496565103530884 + X: -0.17198379337787628 + Y: 0.685264527797699 + Z: -0.4780980944633484 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.785398006439209 + Pitch: 0.5703977942466736 Target Frame: - Yaw: 0.7903980016708374 + Yaw: 0.6753981709480286 Saved: ~ Window Geometry: Camera1 - Depth: @@ -250,10 +273,10 @@ Window Geometry: collapsed: false Displays: collapsed: false - Height: 1376 + Height: 1191 Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 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 + Hide Right Dock: true + QMainWindow State: 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 Selection: collapsed: false Time: @@ -261,7 +284,7 @@ Window Geometry: Tool Properties: collapsed: false Views: - collapsed: false - Width: 2461 - X: 544 - Y: 80 + collapsed: true + Width: 1867 + X: 336 + Y: 48 diff --git a/noetic_ws/src/isaac_tutorials/rviz/turtle_stereo.rviz b/noetic_ws/src/isaac_tutorials/rviz/turtle_stereo.rviz deleted file mode 100644 index ea54f39..0000000 --- a/noetic_ws/src/isaac_tutorials/rviz/turtle_stereo.rviz +++ /dev/null @@ -1,122 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Camera1 - - /Camera2 - Splitter Ratio: 0.6198830604553223 - Tree Height: 525 - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: Camera -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Class: rviz/Camera - Enabled: true - Image Rendering: background and overlay - Image Topic: /rgb - Name: Camera - Overlay Alpha: 0.5 - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - Visibility: - Camera: true - Value: true - Zoom Factor: 1 - - Class: rviz/Camera - Enabled: true - Image Rendering: background and overlay - Image Topic: /rgb_2 - Name: Camera - Overlay Alpha: 0.5 - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - Visibility: - Camera: true - Value: true - Zoom Factor: 1 - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: sim_camera - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 9.993002891540527 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Field of View: 0.7853981852531433 - Focal Point: - X: -0.032822735607624054 - Y: -0.10360819101333618 - Z: 0.054841917008161545 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.8803979158401489 - Target Frame: - Yaw: 0.3453984558582306 - Saved: ~ -Window Geometry: - Camera: - collapsed: false - Displays: - collapsed: false - Height: 846 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000015600000017fc0200000007fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000000000000000fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000001e1fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000010c000001e10000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b2000000000000000000000002000004f300000298fc0100000004fb000000100044006900730070006c0061007900730100000000000001a30000015600fffffffb0000000c00430061006d00650072006101000001a9000001a10000006900fffffffb0000000c00430061006d0065007200610100000350000001a30000006900fffffffb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004f300000039fc0100000002fb0000000800540069006d00650100000000000004f3000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004f30000001700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Time: - collapsed: false - Tool Properties: - collapsed: false - Width: 1267 - X: 367 - Y: 177 diff --git a/noetic_ws/src/navigation/carter_2dnav/rviz/carter_2dnav_rtx.rviz b/noetic_ws/src/isaac_tutorials/rviz/turtlebot_config.rviz similarity index 50% rename from noetic_ws/src/navigation/carter_2dnav/rviz/carter_2dnav_rtx.rviz rename to noetic_ws/src/isaac_tutorials/rviz/turtlebot_config.rviz index e71e07b..c827dcd 100644 --- a/noetic_ws/src/navigation/carter_2dnav/rviz/carter_2dnav_rtx.rviz +++ b/noetic_ws/src/isaac_tutorials/rviz/turtlebot_config.rviz @@ -6,13 +6,9 @@ Panels: Expanded: - /Global Options1 - /Status1 - - /Grid1 - - /Map1 - - /Path1 - - /Map2 - - /Image1 + - /LaserScan1 Splitter Ratio: 0.5 - Tree Height: 411 + Tree Height: 605 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -25,13 +21,12 @@ Panels: - Class: rviz/Views Expanded: - /Current View1 - - /Current View1/Focal Point1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Name: Time SyncMode: 0 - SyncSource: Image + SyncSource: LaserScan Preferences: PromptSaveOnExit: true Toolbars: @@ -54,9 +49,85 @@ Visualization Manager: Y: 0 Z: 0 Plane: XY - Plane Cell Count: 20 + Plane Cell Count: 10 Reference Frame: Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Flat Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /camera_1/depth/image_rect_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Camera1 - Depth + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /camera_2/depth/image_rect_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Camera2 - Depth + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera_1/rgb/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Camera1_RGB + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera_2/rgb/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Camera_2_RGB + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true - Class: rviz/TF Enabled: true Filter (blacklist): "" @@ -64,31 +135,27 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true - base_link: - Value: true - carter_camera_stereo_left: + Camera_1: Value: true - carter_camera_stereo_right: + Camera_2: Value: true - carter_lidar: + Lidar: Value: true - chassis_link: + base_footprint: Value: true - com_offset: + base_link: Value: true - imu: + base_scan: Value: true - left_wheel_link: + caster_back_link: Value: true - map: + imu_link: Value: true odom: Value: true - rear_pivot_link: - Value: true - rear_wheel_link: + wheel_left_link: Value: true - right_wheel_link: + wheel_right_link: Value: true Marker Alpha: 1 Marker Scale: 1 @@ -97,80 +164,56 @@ Visualization Manager: Show Axes: true Show Names: true Tree: - map: - odom: - base_link: - chassis_link: - carter_camera_stereo_left: - {} - carter_camera_stereo_right: - {} - carter_lidar: - {} - com_offset: - {} - imu: - {} - left_wheel_link: - {} - rear_pivot_link: - rear_wheel_link: - {} - right_wheel_link: - {} + odom: + base_link: + Camera_1: + {} + Camera_2: + {} + Lidar: + {} + base_footprint: + {} + base_scan: + {} + caster_back_link: + {} + imu_link: + {} + wheel_left_link: + {} + wheel_right_link: + {} Update Interval: 0 Value: true - - Alpha: 0.699999988079071 - Class: rviz/Map - Color Scheme: map - Draw Behind: false - Enabled: true - Name: Map - Topic: /map - Unreliable: false - Use Timestamp: false - Value: true - Alpha: 1 - Buffer Length: 1 - Class: rviz/Path - Color: 25; 255; 0 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 Enabled: true - Head Diameter: 0.30000001192092896 - Head Length: 0.20000000298023224 - Length: 0.30000001192092896 - Line Style: Lines - Line Width: 0.029999999329447746 - Name: Path - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 255; 85; 255 - Pose Style: None + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: PointCloud2 + Position Transformer: XYZ Queue Size: 10 - Radius: 0.029999999329447746 - Shaft Diameter: 0.10000000149011612 - Shaft Length: 0.10000000149011612 - Topic: /move_base/TrajectoryPlannerROS/global_plan + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /point_cloud Unreliable: false + Use Fixed Frame: true + Use rainbow: true Value: true - - Alpha: 1 - Arrow Length: 0.30000001192092896 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz/PoseArray - Color: 255; 25; 0 - Enabled: false - Head Length: 0.07000000029802322 - Head Radius: 0.029999999329447746 - Name: PoseArray - Queue Size: 10 - Shaft Length: 0.23000000417232513 - Shaft Radius: 0.009999999776482582 - Shape: Arrow (Flat) - Topic: /particlecloud - Unreliable: false - Value: false - Angle Tolerance: 0.10000000149011612 Class: rviz/Odometry Covariance: @@ -188,7 +231,7 @@ Visualization Manager: Scale: 1 Value: true Value: true - Enabled: false + Enabled: true Keep: 100 Name: Odometry Position Tolerance: 0.10000000149011612 @@ -205,157 +248,12 @@ Visualization Manager: Value: Arrow Topic: /odom Unreliable: false - Value: false - - Alpha: 0.699999988079071 - Class: rviz/Map - Color Scheme: map - Draw Behind: false - Enabled: true - Name: Map - Topic: /move_base/local_costmap/costmap - Unreliable: false - Use Timestamp: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /rgb_left - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.10000000149011612 - Name: Pose - Queue Size: 10 - Shaft Length: 1 - Shaft Radius: 0.05000000074505806 - Shape: Arrow - Topic: /move_base_simple/goal - Unreliable: false - Value: true - - Alpha: 1 - Class: rviz/RobotModel - Collision Enabled: false - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - chassis_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - com_offset: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - imu: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - left_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - rear_pivot_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - rear_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - right_wheel_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Name: RobotModel - Robot Description: robot_description - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 3.693763256072998 - Min Value: -0.2574300765991211 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /point_cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/LaserScan - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: LaserScan - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /scan - Unreliable: false - Use Fixed Frame: true - Use rainbow: true Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true - Fixed Frame: map + Fixed Frame: odom Frame Rate: 30 Name: root Tools: @@ -379,7 +277,7 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 41.5562629699707 + Distance: 7.0614471435546875 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -387,27 +285,33 @@ Visualization Manager: Value: false Field of View: 0.7853981852531433 Focal Point: - X: 0.7980453372001648 - Y: 3.087585926055908 - Z: -0.5468370914459229 + X: -0.3891729414463043 + Y: -0.4152672290802002 + Z: -0.6854022145271301 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.9697966575622559 + Pitch: 0.6347964406013489 Target Frame: - Yaw: 6.278185844421387 + Yaw: 0.8253982067108154 Saved: ~ Window Geometry: + Camera1 - Depth: + collapsed: false + Camera1_RGB: + collapsed: false + Camera2 - Depth: + collapsed: false + Camera_2_RGB: + collapsed: false Displays: collapsed: false - Height: 898 + Height: 1191 Hide Left Dock: false Hide Right Dock: true - Image: - collapsed: false - QMainWindow State: 000000ff00000000fd000000040000000000000156000002e8fc020000000efb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001d6000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001a4000000ea0000000000000000fb0000000a0049006d00610067006501000002170000010c0000001600fffffffb0000000a0049006d0061006700650000000225000000ee0000000000000000fb0000000a0049006d0061006700650100000254000000bf0000000000000000fb0000000a0049006d0061006700650000000254000000bf0000000000000000fb0000000a0049006d00610067006501000002250000017b0000000000000000000000010000010f00000365fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b00000365000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005620000003efc0100000002fb0000000800540069006d00650100000000000005620000030700fffffffb0000000800540069006d0065010000000000000450000000000000000000000406000002e800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 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 Selection: collapsed: false Time: @@ -416,6 +320,6 @@ Window Geometry: collapsed: false Views: collapsed: true - Width: 1378 - X: 273 - Y: 84 + Width: 1867 + X: 336 + Y: 27 diff --git a/noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation.launch b/noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation.launch index e14eef8..8d09b29 100644 --- a/noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation.launch +++ b/noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation.launch @@ -23,5 +23,33 @@ + + + + + + target_frame: carter_lidar # Leave disabled to output scan in pointcloud frame + transform_tolerance: 0.01 + min_height: -0.1 + max_height: 2 + + angle_min: -1.5708 # -M_PI/2 + angle_max: 1.5708 # M_PI/2 + angle_increment: 0.0087 # M_PI/360.0 + scan_time: 0.3333 + range_min: 0.15 + range_max: 100.0 + use_inf: true + inf_epsilon: 1.0 + + # Concurrency level, affects number of pointclouds queued for processing and number of threads used + # 0 : Detect number of cores + # 1 : Single threaded + # 2->inf : Parallelism level + concurrency_level: 1 + + + + diff --git a/noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation_rtx.launch b/noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation_rtx.launch deleted file mode 100644 index 7fa7b9d..0000000 --- a/noetic_ws/src/navigation/carter_2dnav/launch/carter_navigation_rtx.launch +++ /dev/null @@ -1,56 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - target_frame: carter_lidar # Leave disabled to output scan in pointcloud frame - transform_tolerance: 0.01 - min_height: -0.1 - max_height: 2 - - angle_min: -1.5708 # -M_PI/2 - angle_max: 1.5708 # M_PI/2 - angle_increment: 0.0087 # M_PI/360.0 - scan_time: 0.3333 - range_min: 0.15 - range_max: 100.0 - use_inf: true - inf_epsilon: 1.0 - - # Concurrency level, affects number of pointclouds queued for processing and number of threads used - # 0 : Detect number of cores - # 1 : Single threaded - # 2->inf : Parallelism level - concurrency_level: 1 - - - - - - - diff --git a/noetic_ws/src/navigation/carter_2dnav/launch/carter_slam_gmapping.launch b/noetic_ws/src/navigation/carter_2dnav/launch/carter_slam_gmapping.launch new file mode 100644 index 0000000..d5ac8ce --- /dev/null +++ b/noetic_ws/src/navigation/carter_2dnav/launch/carter_slam_gmapping.launch @@ -0,0 +1,33 @@ + + + + + + + + + target_frame: carter_lidar # Leave disabled to output scan in pointcloud frame + transform_tolerance: 0.01 + min_height: -0.1 + max_height: 2 + + angle_min: -1.5708 # -M_PI/2 + angle_max: 1.5708 # M_PI/2 + angle_increment: 0.0087 # M_PI/360.0 + scan_time: 0.3333 + range_min: 0.15 + range_max: 100.0 + use_inf: true + inf_epsilon: 1.0 + + # Concurrency level, affects number of pointclouds queued for processing and number of threads used + # 0 : Detect number of cores + # 1 : Single threaded + # 2->inf : Parallelism level + concurrency_level: 1 + + + + + + diff --git a/noetic_ws/src/navigation/carter_2dnav/launch/move_base_individual.launch b/noetic_ws/src/navigation/carter_2dnav/launch/move_base_individual.launch index 30ff001..96eb66e 100644 --- a/noetic_ws/src/navigation/carter_2dnav/launch/move_base_individual.launch +++ b/noetic_ws/src/navigation/carter_2dnav/launch/move_base_individual.launch @@ -72,4 +72,31 @@ + + + + + + transform_tolerance: 0.01 + min_height: -0.1 + max_height: 2 + + angle_min: -1.5708 # -M_PI/2 + angle_max: 1.5708 # M_PI/2 + angle_increment: 0.0087 # M_PI/360.0 + scan_time: 0.3333 + range_min: 0.15 + range_max: 100.0 + use_inf: true + inf_epsilon: 1.0 + + # Concurrency level, affects number of pointclouds queued for processing and number of threads used + # 0 : Detect number of cores + # 1 : Single threaded + # 2->inf : Parallelism level + concurrency_level: 1 + + + + \ No newline at end of file diff --git a/noetic_ws/src/navigation/carter_2dnav/package.xml b/noetic_ws/src/navigation/carter_2dnav/package.xml index 72e5445..2daebeb 100644 --- a/noetic_ws/src/navigation/carter_2dnav/package.xml +++ b/noetic_ws/src/navigation/carter_2dnav/package.xml @@ -1,7 +1,7 @@ carter_2dnav - 0.1.0 + 0.2.0 The carter_2dnav package Isaac Sim diff --git a/noetic_ws/src/navigation/carter_2dnav/rviz/carter_slam_gmapping.rviz b/noetic_ws/src/navigation/carter_2dnav/rviz/carter_slam_gmapping.rviz new file mode 100644 index 0000000..3eac273 --- /dev/null +++ b/noetic_ws/src/navigation/carter_2dnav/rviz/carter_slam_gmapping.rviz @@ -0,0 +1,234 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 267 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /rgb_left + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /base_scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Class: rviz/TF + Enabled: true + Filter (blacklist): "" + Filter (whitelist): "" + Frame Timeout: 15 + Frames: + All Enabled: true + base_link: + Value: true + carter_camera_stereo_left: + Value: true + carter_camera_stereo_right: + Value: true + carter_lidar: + Value: true + chassis_link: + Value: true + com_offset: + Value: true + imu: + Value: true + left_wheel_link: + Value: true + map: + Value: true + odom: + Value: true + rear_pivot_link: + Value: true + rear_wheel_link: + Value: true + right_wheel_link: + Value: true + Marker Alpha: 1 + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + map: + odom: + base_link: + chassis_link: + carter_camera_stereo_left: + {} + carter_camera_stereo_right: + {} + carter_lidar: + {} + com_offset: + {} + imu: + {} + left_wheel_link: + {} + rear_pivot_link: + rear_wheel_link: + {} + right_wheel_link: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 10 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 662 + Hide Left Dock: false + Hide Right Dock: true + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001f8fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000148000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000018b000000aa0000001600ffffff000000010000010f000001f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000001f8000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003bc0000003efc0100000002fb0000000800540069006d00650100000000000003bc000003bc00fffffffb0000000800540069006d0065010000000000000450000000000000000000000260000001f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 956 + X: 68 + Y: 27 diff --git a/ubuntu_20_foxy_minimal.dockerfile b/ubuntu_20_foxy_minimal.dockerfile index e372326..113bd24 100644 --- a/ubuntu_20_foxy_minimal.dockerfile +++ b/ubuntu_20_foxy_minimal.dockerfile @@ -58,6 +58,8 @@ RUN apt update && apt install -y \ libtinyxml2-dev \ libcunit1-dev +RUN pip3 install setuptools==70.0.0 + RUN python3 -m pip install -U \ argcomplete \ flake8-blind-except \ @@ -77,11 +79,10 @@ RUN python3.10 -m pip uninstall numpy -y RUN python3.10 -m pip install --upgrade pip RUN python3.10 -m pip install numpy -RUN pip3 install setuptools==58.2.0 RUN mkdir -p ${ROS_ROOT}/src && \ cd ${ROS_ROOT} && \ - rosinstall_generator --deps --rosdistro ${ROS_DISTRO} rosidl_runtime_c rcutils rcl rmw tf2_msgs geometry_msgs nav_msgs std_msgs rosgraph_msgs sensor_msgs vision_msgs rclpy ros2topic ros2pkg ros2doctor ros2run ros2node ros_environment > ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall && \ + rosinstall_generator --deps --rosdistro ${ROS_DISTRO} rosidl_runtime_c rcutils rcl rmw tf2 tf2_msgs geometry_msgs nav_msgs std_msgs rosgraph_msgs sensor_msgs vision_msgs rclpy ros2topic ros2pkg ros2doctor ros2run ros2node ros_environment ackermann_msgs example_interfaces > ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall && \ cat ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall && \ vcs import src < ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall diff --git a/ubuntu_20_humble_minimal.dockerfile b/ubuntu_20_humble_minimal.dockerfile index 253cc00..e3dd8fb 100644 --- a/ubuntu_20_humble_minimal.dockerfile +++ b/ubuntu_20_humble_minimal.dockerfile @@ -48,6 +48,8 @@ RUN curl -s https://bootstrap.pypa.io/get-pip.py -o get-pip.py && \ RUN wget --no-check-certificate https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc && apt-key add ros.asc RUN sh -c 'echo "deb [arch=$(dpkg --print-architecture)] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" > /etc/apt/sources.list.d/ros2-latest.list' +RUN pip3 install setuptools==70.0.0 + RUN apt update && apt install -y \ python3-pip \ python3-pytest-cov \ @@ -78,11 +80,10 @@ RUN python3.10 -m pip uninstall numpy -y RUN python3.10 -m pip install --upgrade pip RUN python3.10 -m pip install numpy -RUN pip3 install setuptools==58.2. RUN mkdir -p ${ROS_ROOT}/src && \ cd ${ROS_ROOT} && \ - rosinstall_generator --deps --rosdistro ${ROS_DISTRO} rosidl_runtime_c rcutils rcl rmw tf2_msgs geometry_msgs nav_msgs std_msgs rosgraph_msgs sensor_msgs vision_msgs rclpy ros2topic ros2pkg ros2doctor ros2run ros2node ros_environment > ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall && \ + rosinstall_generator --deps --rosdistro ${ROS_DISTRO} rosidl_runtime_c rcutils rcl rmw tf2 tf2_msgs geometry_msgs nav_msgs std_msgs rosgraph_msgs sensor_msgs vision_msgs rclpy ros2topic ros2pkg ros2doctor ros2run ros2node ros_environment ackermann_msgs example_interfaces > ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall && \ cat ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall && \ vcs import src < ros2.${ROS_DISTRO}.${ROS_PKG}.rosinstall