Skip to content

Commit a367cb0

Browse files
Merge pull request #3 from NVIDIA-ISAAC-ROS/hotfix-release-2.1-1
Update Carter launch files
2 parents 2f379d5 + 1f5f212 commit a367cb0

File tree

6 files changed

+55
-72
lines changed

6 files changed

+55
-72
lines changed

carter_navigation/launch/include/front_hawk_ess_nvblox.launch.py

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,13 @@ def launch_setup(context):
142142
]
143143
)
144144

145-
nvblox_config = os.path.join(
145+
nvblox_base_config = os.path.join(
146+
get_package_share_directory('nvblox_examples_bringup'),
147+
'config',
148+
'nvblox',
149+
'nvblox_base.yaml'
150+
)
151+
nvblox_carter_config = os.path.join(
146152
get_package_share_directory('carter_navigation'),
147153
'params',
148154
'nvblox_carter.yaml'
@@ -157,7 +163,7 @@ def launch_setup(context):
157163
('depth/camera_info', 'left/camera_info_resized'),
158164
('color/image', 'left/image_resized'),
159165
('color/camera_info', 'left/camera_info_resized')],
160-
parameters=[nvblox_config]
166+
parameters=[nvblox_base_config, nvblox_carter_config]
161167
)
162168

163169
load_hawk_ess_nvblox = LoadComposableNodes(

carter_navigation/launch/include/segway.launch.py

Lines changed: 19 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -18,27 +18,38 @@
1818
from launch import LaunchDescription
1919
from launch.substitutions import LaunchConfiguration
2020
from launch.actions import DeclareLaunchArgument, TimerAction
21-
from launch_ros.actions import LoadComposableNodes, Node
21+
from launch_ros.actions import ComposableNodeContainer, Node
2222
from launch_ros.descriptions import ComposableNode
2323

2424

2525
def generate_launch_description():
2626
segway_rmp_node = ComposableNode(
2727
package='isaac_ros_segway_rmp',
2828
plugin='nvidia::isaac_ros::segway_rmp::SegwayRMPNode',
29-
name='segway_rmp',
29+
name='segway_rmp',
3030
remappings=[
3131
('/cmd_vel', '/mux/cmd_vel')
32-
]
32+
],
33+
parameters=[{
34+
'enable_statistics': True,
35+
'topics_list': ['odom'],
36+
'expected_fps_list': [40.0],
37+
'jitter_tolerance_us': 50000
38+
}]
3339
)
3440

35-
load_segway = LoadComposableNodes(
36-
target_container='carter_container',
41+
segway_rmp_container = ComposableNodeContainer(
42+
package='rclcpp_components',
43+
name='segway_rmp_container',
44+
namespace='',
45+
prefix="nice -n 1",
46+
executable='component_container_mt',
3747
composable_node_descriptions=[
38-
segway_rmp_node
39-
]
48+
segway_rmp_node,
49+
],
50+
output='screen'
4051
)
4152

4253
return LaunchDescription([
43-
load_segway
54+
segway_rmp_container
4455
])

carter_navigation/launch/nav2.launch.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ def generate_launch_description():
4242
launch_owls_arg = DeclareLaunchArgument('launch_owls', default_value=launch_owls,
4343
description='Launch Owl Cameras')
4444
launch_nvblox_pipeline = LaunchConfiguration(
45-
'launch_nvblox_pipeline', default=False)
45+
'launch_nvblox_pipeline', default=True)
4646
launch_nvblox_pipeline_arg = DeclareLaunchArgument(
4747
'launch_nvblox_pipeline', default_value=launch_nvblox_pipeline,
4848
description='Launch Hawk Camera + ESS Depth + Isaac ROS Nvblox')
@@ -141,6 +141,7 @@ def generate_launch_description():
141141
name='carter_container',
142142
package='rclcpp_components',
143143
executable='component_container_isolated',
144+
prefix="nice -n 2",
144145
parameters=[params_file],
145146
output='screen')
146147

carter_navigation/params/carter_nav2.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -383,7 +383,7 @@ local_costmap:
383383
enabled: True
384384
max_obstacle_distance: 1.0
385385
inflation_distance: 0.4
386-
nvblox_map_slice_topic: "/nvblox_node/map_slice"
386+
nvblox_map_slice_topic: "/hawk_front/nvblox_node/static_map_slice"
387387
always_send_full_costmap: True
388388

389389
global_costmap:
@@ -474,7 +474,7 @@ global_costmap:
474474
enabled: True
475475
max_obstacle_distance: 1.0
476476
inflation_distance: 0.4
477-
nvblox_map_slice_topic: "/nvblox_node/map_slice"
477+
nvblox_map_slice_topic: "/hawk_front/nvblox_node/static_map_slice"
478478
always_send_full_costmap: True
479479

480480
map_server:
Lines changed: 16 additions & 58 deletions
Original file line numberDiff line numberDiff line change
@@ -1,67 +1,25 @@
11
/**:
22
ros__parameters:
3-
# miscellaneous
43
global_frame: map
5-
voxel_size: 0.05
6-
use_tf_transforms: true
7-
# esdf settings
8-
compute_esdf: true
9-
esdf_update_rate_hz: 10.0
10-
esdf_2d: true
11-
esdf_distance_slice: true
12-
esdf_slice_height: 0.5
13-
esdf_2d_min_height: 0.5
14-
esdf_2d_max_height: 1.0
15-
# mesh settings
16-
compute_mesh: true
17-
mesh_update_rate_hz: 5.0
18-
# color settings
19-
use_color: true
20-
max_color_update_hz: 5.0
21-
# depth settings
22-
use_depth: true
23-
max_depth_update_hz: 30.0
24-
# lidar settings
4+
# Lidar settings
255
use_lidar: false
26-
max_lidar_update_hz: 100.0
27-
lidar_width: 1800
28-
lidar_height: 31
29-
# static occupancy
30-
use_static_occupancy_layer: false # tsdf if false
31-
occupancy_publication_rate_hz: 2.0
32-
# Input queues
33-
max_poll_rate_hz: 100.0
34-
maximum_sensor_message_queue_length: 30
6+
# QoS settings
7+
depth_qos: "SENSOR_DATA"
8+
color_qos: "SENSOR_DATA"
359
# Map clearing settings
36-
map_clearing_radius_m: -1.0 # no map clearing if < 0.0
3710
map_clearing_frame_id: "base_link"
38-
clear_outside_radius_rate_hz: 1.0
39-
# QoS settings
40-
depth_qos: "SYSTEM_DEFAULT"
41-
color_qos: "SYSTEM_DEFAULT"
4211
# Rviz visualization
4312
slice_visualization_attachment_frame_id: "base_link"
44-
slice_visualization_side_length: 10.0
4513

46-
mapper:
47-
# tsdf or occupancy integrator
48-
projective_integrator_max_integration_distance_m: 7.0
49-
projective_integrator_truncation_distance_vox: 4.0
50-
lidar_projective_integrator_max_integration_distance_m: 10.0
51-
# tsdf integrator
52-
weighting_mode: "inverse_square" # applies to color integrator as well
53-
tsdf_integrator_max_weight: 5.0
54-
# occupancy integrator
55-
free_region_occupancy_probability: 0.45
56-
occupied_region_occupancy_probability: 0.55
57-
unobserved_region_occupancy_probability: 0.5
58-
occupied_region_half_width_m: 0.1
59-
# esdf integrator
60-
esdf_integrator_min_weight: 0.0001
61-
esdf_integrator_max_distance_m: 2.0
62-
esdf_integrator_max_site_distance_vox: 5.0
63-
# mesh integrator
64-
mesh_integrator_min_weight: 0.0001
65-
mesh_integrator_weld_vertices: true
66-
# color integrator
67-
color_integrator_max_integration_distance_m: 7.0
14+
static_mapper:
15+
esdf_slice_height: 0.1
16+
esdf_slice_min_height: 0.1
17+
esdf_slice_max_height: 0.65
18+
# do not send ceiling:
19+
mesh_streamer_exclusion_height_m: 1.4
20+
mesh_streamer_exclusion_radius_m: 5.0
21+
22+
dynamic_mapper:
23+
esdf_slice_height: 0.0
24+
esdf_slice_min_height: 0.1
25+
esdf_slice_max_height: 0.65

segway_rmp/isaac_ros_segway_rmp/launch/isaac_ros_segway_rmp.launch.py

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,19 @@ def generate_launch_description():
2424
segway_rmp_node = ComposableNode(
2525
package='isaac_ros_segway_rmp',
2626
plugin='nvidia::isaac_ros::segway_rmp::SegwayRMPNode',
27-
name='segway_rmp')
27+
name='segway_rmp',
28+
parameters=[{
29+
'enable_statistics': True,
30+
'topics_list': ['odom'],
31+
'expected_fps_list': [40.0],
32+
'jitter_tolerance_us': 200000
33+
}])
2834

2935
segway_rmp_container = ComposableNodeContainer(
3036
package='rclcpp_components',
3137
name='segway_rmp_container',
3238
namespace='',
39+
prefix="nice -n 1",
3340
executable='component_container_mt',
3441
composable_node_descriptions=[
3542
segway_rmp_node,

0 commit comments

Comments
 (0)