Significantly improved convergence for mesh and cuboid, new ESDF collision.
This commit is contained in:
@@ -40,7 +40,7 @@ cost:
|
||||
|
||||
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: [1.00,1.00,1.00,1.0,1.0,1.0] # running weight orientation, position
|
||||
run_vec_weight: [0.00,0.00,0.00,0.0,0.0,0.0] # running weight orientation, position
|
||||
weight: [2000,50000.0,30,50] #[150.0, 2000.0, 30, 40]
|
||||
vec_convergence: [0.0,0.0] # orientation, position, orientation metric activation, position metric activation
|
||||
terminal: True
|
||||
@@ -54,19 +54,17 @@ cost:
|
||||
|
||||
bound_cfg:
|
||||
weight: [5000.0, 50000.0, 50000.0,50000.0] # needs to be 3 values
|
||||
#weight: [000.0, 000.0, 000.0,000.0]
|
||||
smooth_weight: [0.0,10000.0,10.0, 0.0] # [vel, acc, jerk, alpha_v-not-used]
|
||||
#smooth_weight: [0.0,0000.0,0.0, 0.0] # [vel, acc, jerk, alpha_v-not-used]
|
||||
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
|
||||
activation_distance: [0.1,0.1,0.1,0.1] # for position, velocity, acceleration and jerk
|
||||
null_space_weight: [0.0]
|
||||
|
||||
primitive_collision_cfg:
|
||||
weight: 100000.0
|
||||
use_sweep: True
|
||||
sweep_steps: 6
|
||||
sweep_steps: 4
|
||||
classify: False
|
||||
use_sweep_kernel: True
|
||||
use_speed_metric: True
|
||||
@@ -81,11 +79,11 @@ cost:
|
||||
|
||||
|
||||
lbfgs:
|
||||
n_iters: 125 #175
|
||||
n_iters: 100 #175
|
||||
inner_iters: 25
|
||||
cold_start_n_iters: null
|
||||
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] #
|
||||
line_search_scale: [0.01,0.3,0.7,1.0]
|
||||
fixed_iters: True
|
||||
cost_convergence: 0.01
|
||||
cost_delta_threshold: 2000.0
|
||||
|
||||
Reference in New Issue
Block a user