improved joint space planning

This commit is contained in:
Balakumar Sundaralingam
2024-05-30 14:42:22 -07:00
parent 3bfed9d773
commit 0c51dd2da8
28 changed files with 1135 additions and 213 deletions

View File

@@ -10,7 +10,7 @@
##
robot_cfg:
kinematics:
urdf_path: "robot/jaco/jaco_7s.urdf"
@@ -37,13 +37,13 @@ robot_cfg:
base_link: "root"
ee_link: "j2s7s300_end_effector"
link_names: null
collision_link_names: [
"j2s7s300_link_base", "j2s7s300_link_1", "j2s7s300_link_2",
"j2s7s300_link_3", "j2s7s300_link_4", "j2s7s300_link_5", "j2s7s300_link_6", "j2s7s300_link_7",
"j2s7s300_link_finger_tip_1", "j2s7s300_link_finger_tip_2",
"j2s7s300_link_finger_tip_3",
"j2s7s300_link_finger_3",
"j2s7s300_link_finger_tip_3",
"j2s7s300_link_finger_3",
"j2s7s300_link_finger_2",
"j2s7s300_link_finger_1",
]
@@ -151,37 +151,60 @@ robot_cfg:
collision_sphere_buffer: 0.005
self_collision_ignore: {
"j2s7s300_link_base":["j2s7s300_link_1"],
"j2s7s300_link_1":["j2s7s300_link_2"],
"j2s7s300_link_1":["j2s7s300_link_2"],
"j2s7s300_link_2":["j2s7s300_link_3"],
"j2s7s300_link_3":["j2s7s300_link_4"],
"j2s7s300_link_4":["j2s7s300_link_5"],
"j2s7s300_link_5":["j2s7s300_link_6"],
"j2s7s300_link_6":["j2s7s300_link_7"],
"j2s7s300_link_3":["j2s7s300_link_4"],
"j2s7s300_link_4":["j2s7s300_link_5"],
"j2s7s300_link_5":["j2s7s300_link_6",
"j2s7s300_link_finger_tip_1",
"j2s7s300_link_finger_tip_2",
"j2s7s300_link_finger_tip_3",
"j2s7s300_link_finger_1",
"j2s7s300_link_finger_2",
"j2s7s300_link_finger_3"],
"j2s7s300_link_6":["j2s7s300_link_7",
"j2s7s300_link_finger_tip_1",
"j2s7s300_link_finger_tip_2",
"j2s7s300_link_finger_tip_3",
"j2s7s300_link_finger_1",
"j2s7s300_link_finger_2",
"j2s7s300_link_finger_3"],
"j2s7s300_link_7":[
"j2s7s300_link_finger_tip_1",
"j2s7s300_link_finger_tip_1",
"j2s7s300_link_finger_tip_2",
"j2s7s300_link_finger_tip_3",
"j2s7s300_link_finger_1",
"j2s7s300_link_finger_2",
"j2s7s300_link_finger_3",
],
"j2s7s300_link_finger_3":["j2s7s300_link_finger_tip_3","j2s7s300_link_finger_2",
"j2s7s300_link_finger_1"],
"j2s7s300_link_finger_3":
["j2s7s300_link_finger_tip_3","j2s7s300_link_finger_2",
"j2s7s300_link_finger_1", "j2s7s300_link_finger_tip_1", "j2s7s300_link_finger_tip_2"],
"j2s7s300_link_finger_2":["j2s7s300_link_finger_tip_2", "j2s7s300_link_finger_1",
"j2s7s300_link_finger_3"],
"j2s7s300_link_finger_3", "j2s7s300_link_finger_tip_3", "j2s7s300_link_finger_tip_1"],
"j2s7s300_link_finger_1":["j2s7s300_link_finger_tip_1", "j2s7s300_link_finger_2",
"j2s7s300_link_finger_3"],
"j2s7s300_link_finger_3", "j2s7s300_link_finger_tip_3", "j2s7s300_link_finger_tip_2"],
"j2s7s300_link_finger_tip_1":["j2s7s300_link_finger_tip_2", "j2s7s300_link_finger_tip_3"],
"j2s7s300_link_finger_tip_2":["j2s7s300_link_finger_tip_3"],
} # Dict[str, List[str]]
self_collision_buffer: {} # Dict[str, float]
mesh_link_names: [
self_collision_buffer: {
#"j2s7s300_link_base": 0.02,
#"j2s7s300_link_1": 0.01,
} # Dict[str, float]
mesh_link_names: [
"j2s7s300_link_base", "j2s7s300_link_1", "j2s7s300_link_2",
"j2s7s300_link_3", "j2s7s300_link_4", "j2s7s300_link_5", "j2s7s300_link_6", "j2s7s300_link_7",
"j2s7s300_link_finger_tip_1", "j2s7s300_link_finger_tip_2",
"j2s7s300_link_finger_tip_3",
"j2s7s300_link_finger_3",
"j2s7s300_link_finger_tip_3",
"j2s7s300_link_finger_3",
"j2s7s300_link_finger_2",
"j2s7s300_link_finger_1",
] # List[str]
@@ -191,18 +214,18 @@ robot_cfg:
"j2s7s300_joint_finger_tip_1": 0,
"j2s7s300_joint_finger_tip_2": 0,
"j2s7s300_joint_finger_tip_3": 0,
}
cspace:
joint_names:
joint_names:
- j2s7s300_joint_1
- j2s7s300_joint_2
- j2s7s300_joint_3
- j2s7s300_joint_4
- j2s7s300_joint_5
- j2s7s300_joint_6
- j2s7s300_joint_7
- j2s7s300_joint_7
- j2s7s300_joint_finger_1
- j2s7s300_joint_finger_2
- j2s7s300_joint_finger_3

View File

@@ -11,10 +11,10 @@
world_collision_checker_cfg:
cache: null
cache: null
checker_type: "PRIMITIVE"
max_distance: 0.1
cost:
pose_cfg:
@@ -27,8 +27,8 @@ cost:
weight: [0.0, 0.0]
vec_convergence: [0.0, 0.00] # orientation, position
terminal: False
bound_cfg:
weight: 000.0
activation_distance: [0.0,0.0,0.0,0.0]
@@ -58,14 +58,14 @@ convergence:
weight: [0.1, 10.0]
vec_convergence: [0.0, 0.0] # orientation, position
terminal: False
cspace_cfg:
weight: 1.0
terminal: True
run_weight: 0.0
use_l2_kernel: True
null_space_cfg:
weight: 1.0
weight: 0.001
terminal: True
run_weight: 1.0
use_l2_kernel: True

View File

@@ -49,7 +49,7 @@ cost:
cspace_cfg:
weight: 10000.0
weight: 20000.0
terminal: True
run_weight: 0.00 #1
@@ -59,7 +59,7 @@ cost:
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
activation_distance: [0.05,0.001,0.001,0.001] # for position, velocity, acceleration and jerk
null_space_weight: [0.0]
primitive_collision_cfg:

View File

@@ -40,17 +40,22 @@ cost:
terminal: False
use_metric: True
run_weight: 1.0
cspace_cfg:
weight: 0.000
bound_cfg:
weight: 5000.0
activation_distance: [0.001]
null_space_weight: [0.1]
null_space_weight: [0.001]
use_l2_kernel: True
primitive_collision_cfg:
weight: 5000.0
use_sweep: False
classify: False
activation_distance: 0.01
self_collision_cfg:
weight: 5000.0
classify: False

View File

@@ -48,7 +48,7 @@ cost:
use_metric: True
cspace_cfg:
weight: 10000.0
weight: 20000.0
terminal: True
run_weight: 0.0
@@ -100,7 +100,7 @@ lbfgs:
use_cuda_update_best_kernel: True
use_temporal_smooth: False
sync_cuda_time: True
step_scale: 1.0 #1.0
step_scale: 1.0
last_best: 10
use_coo_sparse: True
debug_info:

View File

@@ -25,7 +25,7 @@ model:
control_space: 'ACCELERATION'
teleport_mode: False
state_finite_difference_mode: "CENTRAL"
cost:
pose_cfg:
@@ -36,16 +36,16 @@ cost:
terminal: True
run_weight: 1.0
use_metric: True
cspace_cfg:
weight: 1000.0
terminal: True
run_weight: 1.0
bound_cfg:
weight: [5000.0, 5000.0,5000.0,000.0]
activation_distance: [0.1,0.1,0.1,0.1] # for position, velocity, acceleration and jerk
smooth_weight: [0.0, 50.0, 0.0,0.0] # [vel, acc, jerk, alpha_vel, eta_position, eta_vel, eta_acc]
smooth_weight: [0.0, 50.0, 0.0,0.0] # [vel, acc, jerk, alpha_vel, eta_position, eta_vel, eta_acc]
run_weight_velocity: 0.0
run_weight_acceleration: 1.0
run_weight_jerk: 1.0
@@ -60,7 +60,7 @@ cost:
use_speed_metric: False
speed_dt: 0.1 # used only for speed metric
activation_distance: 0.025
self_collision_cfg:
weight: 50000.0
classify: False
@@ -83,13 +83,13 @@ mppi:
alpha : 1
num_particles : 400 #10000
update_cov : True
cov_type : "DIAG_A" #
cov_type : "DIAG_A" #
kappa : 0.0001
null_act_frac : 0.05
sample_mode : 'BEST'
base_action : 'REPEAT'
squash_fn : 'CLAMP'
n_problems : 1
n_problems : 1
use_cuda_graph : True
seed : 0
store_debug : False