## ## 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.15 base_ratio: 1.0 max_dt: 0.15 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: [0.00,0.00,0.00,0.0,0.0,0.0] # running weight orientation, position weight: [2000,500000.0,30,60] vec_convergence: [0.0,0.0] # orientation, position, orientation metric activation, position metric activation terminal: True run_weight: 1.0 use_metric: True link_pose_cfg: vec_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # orientation, position for all timesteps run_vec_weight: [0.00,0.00,0.00,0.0,0.0,0.0] # running weight orientation, position weight: [2000,500000.0,30,60] #[150.0, 2000.0, 30, 40] vec_convergence: [0.0,0.0] # orientation, position, orientation metric activation, position metric activation terminal: True run_weight: 1.0 use_metric: True cspace_cfg: weight: 10000.0 terminal: True run_weight: 0.00 #1 bound_cfg: weight: [10000.0, 500000.0, 500.0, 500.0] smooth_weight: [0.0,10000.0, 5.0, 0.0] run_weight_velocity: 0.0 run_weight_acceleration: 1.0 run_weight_jerk: 1.0 activation_distance: [0.05,0.05,0.05,0.05] # for position, velocity, acceleration and jerk null_space_weight: [0.0] primitive_collision_cfg: weight: 1000000 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: 400 inner_iters: 25 cold_start_n_iters: null min_iters: 25 line_search_scale: [0.1, 0.3, 0.7,1.0] # # fixed_iters: True cost_convergence: 0.001 cost_delta_threshold: 0.0001 cost_relative_threshold: 0.99 epsilon: 0.01 history: 27 use_cuda_graph: True n_problems: 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 last_best: 10 use_coo_sparse: True debug_info: visual_traj : null #'ee_pos_seq'