Skip to content

Commit 4a4ad07

Browse files
authored
Supporting configuring model_configure_timeout_seconds param (#477)
* Expose configure timeout Signed-off-by: Ian Chen <iche@intrinsic.ai> * fix doc Signed-off-by: Ian Chen <iche@intrinsic.ai> --------- Signed-off-by: Ian Chen <iche@intrinsic.ai>
1 parent fea8f0c commit 4a4ad07

File tree

2 files changed

+12
-1
lines changed

2 files changed

+12
-1
lines changed

aic_bringup/launch/aic_gz_bringup.launch.py

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -98,6 +98,9 @@ def launch_setup(context, *args, **kwargs):
9898
model_discovery_timeout_seconds = LaunchConfiguration(
9999
"model_discovery_timeout_seconds"
100100
)
101+
model_configure_timeout_seconds = LaunchConfiguration(
102+
"model_configure_timeout_seconds"
103+
)
101104

102105
gripper_initial_pos = "0.00655"
103106
cable_type_str = LaunchConfiguration("cable_type").perform(context)
@@ -245,6 +248,7 @@ def launch_setup(context, *args, **kwargs):
245248
"config_file_path": aic_engine_config_file,
246249
"use_sim_time": True,
247250
"model_discovery_timeout_seconds": model_discovery_timeout_seconds,
251+
"model_configure_timeout_seconds": model_configure_timeout_seconds,
248252
},
249253
],
250254
condition=IfCondition(start_aic_engine),
@@ -767,6 +771,13 @@ def generate_launch_description():
767771
description="Absolute path to YAML file with the AIC engine configuration.",
768772
)
769773
)
774+
declared_arguments.append(
775+
DeclareLaunchArgument(
776+
"model_configure_timeout_seconds",
777+
default_value="60",
778+
description="Timeout for model configuration checks.",
779+
)
780+
)
770781

771782
declared_arguments.append(
772783
DeclareLaunchArgument(

aic_engine/README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ ros2 run aic_engine aic_engine --ros-args \
5959
-p ground_truth:=false \
6060
-p endpoint_ready_timeout_seconds:=10 \
6161
-p model_discovery_timeout_seconds:=30 \
62-
-p model_configuration_timeout_seconds:=60
62+
-p model_configure_timeout_seconds:=60 \
6363
-p use_sim_time:=true
6464
```
6565

0 commit comments

Comments
 (0)