Significantly improved convergence for mesh and cuboid, new ESDF collision.
This commit is contained in:
@@ -280,6 +280,7 @@
|
||||
<origin rpy="0 0 0" xyz="0 -0.04 0.0584"/>
|
||||
<axis xyz="0 -1 0"/>
|
||||
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
|
||||
<mimic joint="panda_finger_joint1"/>
|
||||
</joint>
|
||||
<link name="right_gripper">
|
||||
<inertial>
|
||||
|
||||
@@ -13,7 +13,7 @@ robot_cfg:
|
||||
kinematics:
|
||||
use_usd_kinematics: False
|
||||
isaac_usd_path: "/Isaac/Robots/Franka/franka.usd"
|
||||
usd_path: "robot/franka/franka_panda.usda"
|
||||
usd_path: "robot/non_shipping/franka/franka_panda_meters.usda"
|
||||
usd_robot_root: "/panda"
|
||||
usd_flip_joints: ["panda_joint1","panda_joint2","panda_joint3","panda_joint4", "panda_joint5",
|
||||
"panda_joint6","panda_joint7","panda_finger_joint1", "panda_finger_joint2"]
|
||||
|
||||
@@ -39,7 +39,13 @@ robot_cfg:
|
||||
}
|
||||
urdf_path: robot/iiwa_allegro_description/iiwa.urdf
|
||||
asset_root_path: robot/iiwa_allegro_description
|
||||
|
||||
mesh_link_names:
|
||||
- iiwa7_link_1
|
||||
- iiwa7_link_2
|
||||
- iiwa7_link_3
|
||||
- iiwa7_link_4
|
||||
- iiwa7_link_5
|
||||
- iiwa7_link_6
|
||||
cspace:
|
||||
joint_names:
|
||||
[
|
||||
|
||||
@@ -30,6 +30,25 @@ robot_cfg:
|
||||
- ring_link_3
|
||||
- thumb_link_2
|
||||
- thumb_link_3
|
||||
mesh_link_names:
|
||||
- iiwa7_link_1
|
||||
- iiwa7_link_2
|
||||
- iiwa7_link_3
|
||||
- iiwa7_link_4
|
||||
- iiwa7_link_5
|
||||
- iiwa7_link_6
|
||||
- palm_link
|
||||
- index_link_1
|
||||
- index_link_2
|
||||
- index_link_3
|
||||
- middle_link_1
|
||||
- middle_link_2
|
||||
- middle_link_3
|
||||
- ring_link_1
|
||||
- ring_link_2
|
||||
- ring_link_3
|
||||
- thumb_link_2
|
||||
- thumb_link_3
|
||||
collision_sphere_buffer: 0.005
|
||||
collision_spheres: spheres/iiwa_allegro.yml
|
||||
ee_link: palm_link
|
||||
|
||||
@@ -134,11 +134,11 @@ collision_spheres:
|
||||
"radius": 0.022
|
||||
panda_leftfinger:
|
||||
- "center": [0.0, 0.01, 0.043]
|
||||
"radius": 0.011 # 25
|
||||
"radius": 0.011 #0.025 # 0.011
|
||||
- "center": [0.0, 0.02, 0.015]
|
||||
"radius": 0.011 # 25
|
||||
"radius": 0.011 #0.025 # 0.011
|
||||
panda_rightfinger:
|
||||
- "center": [0.0, -0.01, 0.043]
|
||||
"radius": 0.011 #25
|
||||
"radius": 0.011 #0.025 #0.011
|
||||
- "center": [0.0, -0.02, 0.015]
|
||||
"radius": 0.011 #25
|
||||
"radius": 0.011 #0.025 #0.011
|
||||
@@ -58,7 +58,7 @@ collision_spheres:
|
||||
radius: 0.07
|
||||
tool0:
|
||||
- center: [0, 0, 0.12]
|
||||
radius: 0.05
|
||||
radius: -0.01
|
||||
camera_mount:
|
||||
- center: [0, 0.11, -0.01]
|
||||
radius: 0.06
|
||||
@@ -38,7 +38,7 @@ robot_cfg:
|
||||
'wrist_1_link': 0,
|
||||
'wrist_2_link': 0,
|
||||
'wrist_3_link' : 0,
|
||||
'tool0': 0,
|
||||
'tool0': 0.05,
|
||||
}
|
||||
mesh_link_names: [ 'shoulder_link','upper_arm_link', 'forearm_link', 'wrist_1_link', 'wrist_2_link' ,'wrist_3_link' ]
|
||||
lock_joints: null
|
||||
|
||||
@@ -92,7 +92,7 @@ robot_cfg:
|
||||
"radius": 0.043
|
||||
tool0:
|
||||
- "center": [0.001, 0.001, 0.05]
|
||||
"radius": 0.05
|
||||
"radius": -0.01 #0.05
|
||||
|
||||
|
||||
collision_sphere_buffer: 0.005
|
||||
@@ -109,6 +109,7 @@ robot_cfg:
|
||||
'wrist_1_link': 0,
|
||||
'wrist_2_link': 0,
|
||||
'wrist_3_link' : 0,
|
||||
'tool0': 0.025,
|
||||
}
|
||||
|
||||
use_global_cumul: True
|
||||
|
||||
@@ -55,17 +55,17 @@ cost:
|
||||
|
||||
bound_cfg:
|
||||
weight: [5000.0, 50000.0, 50000.0, 50000.0] # needs to be 3 values
|
||||
smooth_weight: [0.0,5000.0, 50.0, 0.0] # [vel, acc, jerk,]
|
||||
smooth_weight: [0.0,5000.0, 50.0, 0.0] #[0.0,5000.0, 50.0, 0.0] # [vel, acc, jerk,]
|
||||
run_weight_velocity: 0.0
|
||||
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: 1000000.0
|
||||
weight: 1000000.0 #1000000.0 1000000
|
||||
use_sweep: True
|
||||
sweep_steps: 6
|
||||
sweep_steps: 4
|
||||
classify: False
|
||||
use_sweep_kernel: True
|
||||
use_speed_metric: True
|
||||
@@ -79,7 +79,7 @@ cost:
|
||||
|
||||
|
||||
lbfgs:
|
||||
n_iters: 400 # 400
|
||||
n_iters: 300 # 400
|
||||
inner_iters: 25
|
||||
cold_start_n_iters: null
|
||||
min_iters: 25
|
||||
@@ -89,7 +89,7 @@ lbfgs:
|
||||
cost_delta_threshold: 1.0
|
||||
cost_relative_threshold: 0.999 #0.999
|
||||
epsilon: 0.01
|
||||
history: 15 #15
|
||||
history: 27 #15
|
||||
use_cuda_graph: True
|
||||
n_problems: 1
|
||||
store_debug: False
|
||||
|
||||
@@ -47,7 +47,7 @@ cost:
|
||||
activation_distance: [0.1]
|
||||
null_space_weight: [1.0]
|
||||
primitive_collision_cfg:
|
||||
weight: 50000.0
|
||||
weight: 5000.0
|
||||
use_sweep: False
|
||||
classify: False
|
||||
activation_distance: 0.01
|
||||
@@ -57,11 +57,11 @@ cost:
|
||||
|
||||
|
||||
lbfgs:
|
||||
n_iters: 100 #60
|
||||
inner_iters: 25
|
||||
n_iters: 80 #60
|
||||
inner_iters: 20
|
||||
cold_start_n_iters: null
|
||||
min_iters: 20
|
||||
line_search_scale: [0.01, 0.3, 0.7, 1.0]
|
||||
line_search_scale: [0.1, 0.3, 0.7, 1.0]
|
||||
fixed_iters: True
|
||||
cost_convergence: 1e-7
|
||||
cost_delta_threshold: 1e-6 #0.0001
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -33,7 +33,7 @@ graph:
|
||||
sample_pts: 1500
|
||||
node_similarity_distance: 0.1
|
||||
|
||||
rejection_ratio: 20
|
||||
rejection_ratio: 10
|
||||
k_nn: 15
|
||||
max_buffer: 10000
|
||||
max_cg_buffer: 1000
|
||||
|
||||
@@ -34,7 +34,7 @@ cost:
|
||||
run_weight: 1.0
|
||||
link_pose_cfg:
|
||||
vec_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
|
||||
weight: [30, 50, 10, 10] #[20.0, 100.0]
|
||||
weight: [0, 50, 10, 10] #[20.0, 100.0]
|
||||
vec_convergence: [0.00, 0.000] # orientation, position
|
||||
terminal: False
|
||||
use_metric: True
|
||||
@@ -67,7 +67,7 @@ mppi:
|
||||
cov_type : "DIAG_A" #
|
||||
kappa : 0.01
|
||||
null_act_frac : 0.0
|
||||
sample_mode : 'BEST'
|
||||
sample_mode : 'MEAN'
|
||||
base_action : 'REPEAT'
|
||||
squash_fn : 'CLAMP'
|
||||
n_problems : 1
|
||||
|
||||
@@ -89,7 +89,7 @@ mppi:
|
||||
sample_mode : 'BEST'
|
||||
base_action : 'REPEAT'
|
||||
squash_fn : 'CLAMP'
|
||||
n_problems : 1
|
||||
n_problems : 1
|
||||
use_cuda_graph : True
|
||||
seed : 0
|
||||
store_debug : False
|
||||
|
||||
@@ -39,7 +39,7 @@ cost:
|
||||
|
||||
link_pose_cfg:
|
||||
vec_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
|
||||
run_vec_weight: [0.00,0.00,0.00,0.0,0.0,0.0] # running weight orientation, position
|
||||
run_vec_weight: [0.0,0.0,0.0,0.0,0.0,0.0] # running weight
|
||||
weight: [0.0, 5000.0, 40, 40]
|
||||
vec_convergence: [0.0,0.0,1000.0,1000.0]
|
||||
terminal: True
|
||||
@@ -63,11 +63,11 @@ cost:
|
||||
|
||||
primitive_collision_cfg:
|
||||
weight: 5000.0
|
||||
use_sweep: True
|
||||
use_sweep: False
|
||||
classify: False
|
||||
sweep_steps: 4
|
||||
use_sweep_kernel: True
|
||||
use_speed_metric: True
|
||||
use_sweep_kernel: False
|
||||
use_speed_metric: False
|
||||
speed_dt: 0.01 # used only for speed metric
|
||||
activation_distance: 0.025
|
||||
|
||||
@@ -92,7 +92,7 @@ mppi:
|
||||
cov_type : "DIAG_A" #
|
||||
kappa : 0.001
|
||||
null_act_frac : 0.0
|
||||
sample_mode : 'BEST'
|
||||
sample_mode : 'MEAN'
|
||||
base_action : 'REPEAT'
|
||||
squash_fn : 'CLAMP'
|
||||
n_problems : 1
|
||||
|
||||
Reference in New Issue
Block a user