Skip to content

Commit

Permalink
Isaac ROS 0.10.1 (DP)
Browse files Browse the repository at this point in the history
  • Loading branch information
hemalshahNV committed Jul 12, 2022
1 parent bb804c1 commit 1f3489e
Show file tree
Hide file tree
Showing 14 changed files with 146 additions and 78 deletions.
1 change: 0 additions & 1 deletion .gitattributes
Original file line number Diff line number Diff line change
Expand Up @@ -15,5 +15,4 @@

# ROS Bag
nvblox_nav2/test/test_cases/rosbags/** filter=lfs diff=lfs merge=lfs -text
resources/rosbags** filter=lfs diff=lfs merge=lfs -text

8 changes: 6 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ The figure below shows a simple system utilizing nvblox for path planning.
- [Docker](#docker)
- [Quickstart](#quickstart)
- [Next Steps](#next-steps)
- [Try More Examples](#try-more-examples)
- [Customize your Dev Environment](#customize-your-dev-environment)
- [Package Reference](#package-reference)
- [`nvblox_nav2`](#nvblox_nav2)
Expand Down Expand Up @@ -86,7 +87,7 @@ To simplify development, we strongly recommend leveraging the Isaac ROS Dev Dock

```bash
cd /workspaces/isaac_ros-dev/ && \
rosdep install -i -r --from-paths src --rosdistro humble -y --skip-keys "libopencv-dev libopencv-contrib-dev libopencv-imgproc-dev python-opencv python3-opencv"
rosdep install -i -r --from-paths src --rosdistro humble -y --skip-keys "libopencv-dev libopencv-contrib-dev libopencv-imgproc-dev python-opencv python3-opencv nvblox"
```

6. Build and source the workspace:
Expand Down Expand Up @@ -115,11 +116,14 @@ To simplify development, we strongly recommend leveraging the Isaac ROS Dev Dock

10. In the **second terminal**, play the ROS Bag:
```bash
ros2 bag play src/isaac_ros_nvblox/nvblox_nav2/test/test_cases/rosbags/nvblox_pol
ros2 bag play src/isaac_ros_nvblox/nvblox_nav2/test/test_cases/rosbags/nvblox_pol --remap left/depth:=depth_left left/camera_info:=camera_info_left left/rgb:=rgb_left
```
You should see the robot reconstructing a mesh, with a costmap overlaid on top.

## Next Steps
### Try More Examples
To continue your exploration, check out the following suggested examples:
- [Tutorial with Isaac Sim](./docs/tutorial-isaac-sim.md)
### Customize your Dev Environment
To customize your development environment, reference [this guide](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/docs/modify-dockerfile.md).

Expand Down
28 changes: 28 additions & 0 deletions docs/tutorial-isaac-sim.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# Tutorial with Isaac Sim
> **Note: Isaac Sim 2022.1.0 published on 6/3/2022 does not support ROS2 Humble. Please follow one of the [workarounds](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/docs/isaac-sim-sil-setup.md#isaac-sim-202210-workarounds) before continuing with the tutorial**
1. Complete the [Quickstart section](../README.md#quickstart) in the main README.
2. Launch the Docker container using the `run_dev.sh` script:
```bash
cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \
./scripts/run_dev.sh
```
3. Inside the container, build and source the workspace:
```bash
cd /workspaces/isaac_ros-dev && \
colcon build --symlink-install && \
source install/setup.bash
```
4. Install Isaac Sim following the steps in the [Isaac ROS Isaac Sim Setup Guide](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/docs/isaac-sim-sil-setup.md)
5. Start the simulation by running the below command in a terminal **outside the Docker container**:
```bash
alias omni_python='~/.local/share/ov/pkg/isaac_sim-2022.1.0/python.sh' && \
omni_python ~/workspaces/isaac_ros-dev/src/isaac_ros_nvblox/nvblox_isaac_sim/omniverse_scripts/carter_warehouse.py
```
> **Note:** If you are using a different version of Isaac Sim, replace `isaac_sim-2022.1.0` with your version found at `'~/.local/share/ov/pkg/`
6. Launch the pre-composed pipeline launchfile:
```bash
ros2 launch nvblox_nav2 carter_sim.launch.py
```
7. Click on the `2D Goal Pose` button. You should see the mesh, costmap, and the robot moving towards the goal location as shown below:
<div align="center"><img src="../resources/isaac_sim_nvblox_nav2.gif"/></div>
39 changes: 13 additions & 26 deletions nvblox_nav2/launch/carter_sim.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,6 @@


def generate_launch_description():

use_sim_time = LaunchConfiguration('use_sim_time', default='True')

param_dir = LaunchConfiguration(
'params_file',
default=os.path.join(
Expand All @@ -43,8 +40,6 @@ def generate_launch_description():
rviz_config_dir = os.path.join(get_package_share_directory(
'nvblox_nav2'), 'config', 'carter_nvblox_nav2.rviz')

lifecycle_nodes = ['map_server']

return LaunchDescription(
[
DeclareLaunchArgument(
Expand All @@ -59,13 +54,6 @@ def generate_launch_description():
DeclareLaunchArgument(
'run_nav2', default_value='True',
description='Whether to run nav2'),
Node(
package='nav2_lifecycle_manager', executable='lifecycle_manager',
name='lifecycle_manager_map', output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'autostart': True},
{'node_names': lifecycle_nodes}],
condition=IfCondition(LaunchConfiguration('run_nav2'))),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(nav2_bringup_launch_dir, 'rviz_launch.py')),
Expand All @@ -77,25 +65,24 @@ def generate_launch_description():
PythonLaunchDescriptionSource(
os.path.join(
nav2_bringup_launch_dir, 'navigation_launch.py')),
launch_arguments={'use_sim_time': use_sim_time,
'params_file': param_dir, 'autostart': 'True'}.items(),
condition=IfCondition(
LaunchConfiguration('run_nav2')),
),
launch_arguments={
'use_sim_time': LaunchConfiguration('use_sim_time'),
'params_file': param_dir, 'autostart': 'True',
'use_composition': 'False'}.items(),
condition=IfCondition(LaunchConfiguration('run_nav2')),),
Node(
package='nvblox_ros', executable='nvblox_node',
parameters=[nvblox_param_dir, {'use_sim_time': use_sim_time}],
parameters=[nvblox_param_dir,
{'use_sim_time': LaunchConfiguration('use_sim_time')}],
output='screen',
remappings=[('depth/image', '/left/depth'),
('depth/camera_info', '/left/camera_info'),
('color/image', '/left/rgb'),
('color/camera_info', '/left/camera_info'), ]),
remappings=[('depth/image', '/depth_left'),
('depth/camera_info', '/camera_info_left'),
('color/image', '/rgb_left'),
('color/camera_info', '/camera_info_left'), ]),
Node(
package='tf2_ros', executable='static_transform_publisher',
parameters=[{'use_sim_time': use_sim_time}],
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}],
output='screen',
arguments=['0.0', '0.0', '-0.3', '0.0', '0.0', '0.0', 'map',
'odom'],
condition=IfCondition(
LaunchConfiguration('run_nav2'))),
])
condition=IfCondition(LaunchConfiguration('run_nav2'))), ])
3 changes: 2 additions & 1 deletion nvblox_nav2/launch/carter_sim_elbrus.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,8 @@ def generate_launch_description():
os.path.join(
nav2_bringup_launch_dir, 'navigation_launch.py')),
launch_arguments={'use_sim_time': use_sim_time,
'params_file': param_dir, 'autostart': 'True'}.items(),
'params_file': param_dir,
'autostart': 'True'}.items(),
condition=IfCondition(
LaunchConfiguration('run_nav2'))
),
Expand Down
127 changes: 90 additions & 37 deletions nvblox_nav2/params/carter_nav2.yaml
Original file line number Diff line number Diff line change
@@ -1,31 +1,59 @@
bt_navigator:
ros__parameters:
use_sim_time: True
global_frame: map
global_frame: odom
robot_base_frame: base_link
odom_topic: /odom
default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
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_back_up_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:
Expand All @@ -38,8 +66,9 @@ controller_server:
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: "goal_checker"
goal_checker_plugin: ["general_goal_checker"]
controller_plugins: ["FollowPath"]

# Progress checker parameters
Expand All @@ -48,7 +77,7 @@ controller_server:
required_movement_radius: 0.5
movement_time_allowance: 10.0
# Goal checker parameters
goal_checker:
general_goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
Expand All @@ -59,7 +88,7 @@ controller_server:
debug_trajectory_details: True
min_vel_x: 0.0
min_vel_y: 0.0
max_vel_x: 3.0
max_vel_x: 1.0
max_vel_y: 0.0
max_vel_theta: 0.5
min_speed_xy: 0.0
Expand Down Expand Up @@ -103,26 +132,23 @@ controller_server_rclcpp_node:
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 4.0
publish_frequency: 4.0
global_frame: map
update_frequency: 10.0
publish_frequency: 10.0
global_frame: odom
robot_base_frame: base_link
use_sim_time: True
rolling_window: True
width: 20
height: 20
resolution: 0.05
robot_radius: 0.36
width: 10
height: 10
resolution: 0.10
robot_radius: 0.4
plugins: ["nvblox_layer"]
nvblox_layer:
plugin: "nvblox::nav2::NvbloxCostmapLayer"
enabled: True
max_obstacle_distance: 1.2
inflation_distance: 0.6
max_obstacle_distance: 1.0
inflation_distance: 0.4
always_send_full_costmap: True
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
local_costmap_client:
ros__parameters:
use_sim_time: True
Expand All @@ -133,24 +159,24 @@ local_costmap:
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
update_frequency: 10.0
publish_frequency: 10.0
global_frame: odom
robot_base_frame: base_link
use_sim_time: True
rolling_window: False
rolling_window: True
width: 200
height: 200
robot_radius: 0.36
resolution: 0.05
robot_radius: 0.4
resolution: 0.10
origin_x: -100.0
origin_y: -100.0
plugins: ["nvblox_layer"]
nvblox_layer:
plugin: "nvblox::nav2::NvbloxCostmapLayer"
enabled: True
max_obstacle_distance: 1.2
inflation_distance: 0.6
max_obstacle_distance: 1.0
inflation_distance: 0.4
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
enabled: True
Expand All @@ -169,18 +195,19 @@ global_costmap:
map_server:
ros__parameters:
use_sim_time: True
yaml_filename: "carter_warehouse_navigation.yaml"
yaml_filename: "turtlebot3_world.yaml"

map_saver:
ros__parameters:
use_sim_time: True
save_map_timeout: 5000
save_map_timeout: 5.0
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: True

planner_server:
ros__parameters:
expected_planner_frequency: 4.0
expected_planner_frequency: 20.0
use_sim_time: True
planner_plugins: ["GridBased"]
GridBased:
Expand All @@ -193,24 +220,50 @@ planner_server_rclcpp_node:
ros__parameters:
use_sim_time: True

recoveries_server:
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: 10.0
recovery_plugins: ["spin", "backup", "wait"]
cycle_frequency: 5.0
behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"]
spin:
plugin: "nav2_recoveries/Spin"
plugin: "nav2_behaviors/Spin"
backup:
plugin: "nav2_recoveries/BackUp"
plugin: "nav2_behaviors/BackUp"
drive_on_heading:
plugin: "nav2_behaviors/DriveOnHeading"
wait:
plugin: "nav2_recoveries/Wait"
plugin: "nav2_behaviors/Wait"
global_frame: odom
robot_base_frame: base_link
transform_timeout: 0.1
use_sim_time: True
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:
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

Loading

0 comments on commit 1f3489e

Please sign in to comment.