release repository

This commit is contained in:
Balakumar Sundaralingam
2023-10-26 04:17:19 -07:00
commit 07e6ccfc91
287 changed files with 70659 additions and 0 deletions

View File

@@ -0,0 +1,98 @@
##
## Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
##
## NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
## property and proprietary rights in and to this material, related
## documentation and any modifications thereto. Any use, reproduction,
## disclosure or distribution of this material and related documentation
## without an express license agreement from NVIDIA CORPORATION or
## its affiliates is strictly prohibited.
##
model:
horizon: 32
state_filter_cfg:
filter_coeff:
position: 1.0
velocity: 1.0
acceleration: 1.0
enable: False
dt_traj_params:
base_dt: 0.2
base_ratio: 1.0
max_dt: 0.2
vel_scale: 1.0
control_space: 'POSITION'
state_finite_difference_mode: "CENTRAL"
teleport_mode: False
return_full_act_buffer: True
cost:
pose_cfg:
vec_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # orientation, position for all timesteps
run_vec_weight: [1.00,1.00,1.00,1.0,1.0,1.0] # running weight orientation, position
weight: [2000,20000.0,30,30] #[150.0, 2000.0, 30, 40]
vec_convergence: [0.0,0.0] # orientation, position, orientation metric activation, position metric activation
terminal: True
run_weight: 0.0 #0.05
use_metric: True
cspace_cfg:
weight: 10000.0
terminal: True
run_weight: 0.00 #1
bound_cfg:
weight: [5000.0, 5000.0, 5000.0,5000.0] # needs to be 3 values
smooth_weight: [0.0,3000.0,10.0, 0.0] # [vel, acc, jerk,]
run_weight_velocity: 0.00
run_weight_acceleration: 1.0
run_weight_jerk: 1.0
activation_distance: [0.1,0.1,0.1,10.0] # for position, velocity, acceleration and jerk
null_space_weight: [1.0]
primitive_collision_cfg:
weight: 10000.0
use_sweep: True
sweep_steps: 4
classify: False
use_sweep_kernel: True
use_speed_metric: True
speed_dt: 0.01 # used only for speed metric
activation_distance: 0.025
self_collision_cfg:
weight: 5000.0
classify: False
lbfgs:
n_iters: 100 #125 #@200 #250 #250 # 150 #25
inner_iters: 25 #25 # 25
cold_start_n_iters: 100 #125 #200 #250 #$150 #25
min_iters: 25
line_search_scale: [0.01,0.3,0.7,1.0] #[0.01,0.2, 0.3,0.5,0.7,0.9, 1.0] #
fixed_iters: False
cost_convergence: 0.01
cost_delta_threshold: 1.0
cost_relative_threshold: 0.9999
epsilon: 0.01
history: 4 #15 #$14
use_cuda_graph: True
n_envs: 1
store_debug: False
use_cuda_kernel: True
stable_mode: True
line_search_type: "approx_wolfe"
use_cuda_line_search_kernel: True
use_cuda_update_best_kernel: True
use_temporal_smooth: False
sync_cuda_time: True
step_scale: 1.0 #1.0
last_best: 5
use_coo_sparse: True
debug_info:
visual_traj : null #'ee_pos_seq'