constrained planning, robot segmentation
This commit is contained in:
@@ -172,7 +172,7 @@
|
||||
<dynamics damping="10.0"/>
|
||||
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/>
|
||||
</joint>
|
||||
<!--
|
||||
|
||||
<link name="panda_link8"/>
|
||||
<joint name="panda_joint8" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.107"/>
|
||||
@@ -180,18 +180,11 @@
|
||||
<child link="panda_link8"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
Removing this joint seems to help with some stability things
|
||||
-->
|
||||
<joint name="panda_hand_joint" type="fixed">
|
||||
<!--
|
||||
<parent link="panda_link8"/>
|
||||
-->
|
||||
<parent link="panda_link7"/>
|
||||
<child link="panda_hand"/>
|
||||
<origin rpy="0 0 -0.785398163397" xyz="0 0 0.107"/>
|
||||
<!--
|
||||
|
||||
<origin rpy="0 0 -0.785398163397" xyz="0 0 0"/>
|
||||
-->
|
||||
</joint>
|
||||
<link name="panda_hand">
|
||||
<visual>
|
||||
|
||||
@@ -13,7 +13,7 @@ robot_cfg:
|
||||
kinematics:
|
||||
use_usd_kinematics: False
|
||||
isaac_usd_path: "/Isaac/Robots/Franka/franka.usd"
|
||||
usd_path: "robot/non_shipping/franka/franka_panda_meters.usda"
|
||||
usd_path: "robot/franka/franka_panda.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"]
|
||||
@@ -32,7 +32,7 @@ robot_cfg:
|
||||
usd_flip_joint_limits: ["panda_finger_joint2"]
|
||||
urdf_path: "robot/franka_description/franka_panda.urdf"
|
||||
asset_root_path: "robot/franka_description"
|
||||
base_link: "base_link"
|
||||
base_link: "panda_link0"
|
||||
ee_link: "panda_hand"
|
||||
collision_link_names:
|
||||
[
|
||||
@@ -50,7 +50,7 @@ robot_cfg:
|
||||
"attached_object",
|
||||
]
|
||||
collision_spheres: "spheres/franka_mesh.yml"
|
||||
collision_sphere_buffer: 0.0025
|
||||
collision_sphere_buffer: 0.004 # 0.0025
|
||||
extra_collision_spheres: {"attached_object": 4}
|
||||
use_global_cumul: True
|
||||
self_collision_ignore:
|
||||
|
||||
@@ -109,7 +109,7 @@ robot_cfg:
|
||||
"base_x", "base_y", "base_z",
|
||||
"panda_joint1","panda_joint2","panda_joint3","panda_joint4", "panda_joint5",
|
||||
"panda_joint6","panda_joint7","panda_finger_joint1", "panda_finger_joint2"]
|
||||
retract_config: [0,0,0,0.0, -1.3, 0.0, -2.5, 0.0, 1.0, 0., 0.04, 0.04]
|
||||
retract_config: [0,0,0,0, -1.3, 0.0, -2.5, 0.0, 1.0, 0., 0.04, 0.04]
|
||||
null_space_weight: [1,1,1,1,1,1,1,1,1,1,1,1]
|
||||
cspace_distance_weight: [1,1,1,1,1,1,1,1,1,1,1,1]
|
||||
max_acceleration: 15.0 #15.0
|
||||
|
||||
@@ -12,7 +12,7 @@
|
||||
robot_cfg:
|
||||
kinematics:
|
||||
use_usd_kinematics: False
|
||||
usd_path: "robot/non_shipping/techman/tm12.usd"
|
||||
usd_path: "robot/techman/tm12.usd"
|
||||
usd_robot_root: "/tm12"
|
||||
usd_flip_joints:
|
||||
{
|
||||
|
||||
@@ -49,7 +49,7 @@ robot_cfg:
|
||||
- "center": [-0.055, 0.008, 0.14]
|
||||
"radius": 0.07
|
||||
- "center": [-0.001, -0.002, 0.143]
|
||||
"radius": 0.076
|
||||
"radius": 0.08
|
||||
forearm_link:
|
||||
- "center": [-0.01, 0.002, 0.031]
|
||||
"radius": 0.072
|
||||
|
||||
@@ -31,22 +31,23 @@ model:
|
||||
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,500000.0,30,50] #[150.0, 2000.0, 30, 40]
|
||||
run_vec_weight: [0.00,0.00,0.00,0.0,0.0,0.0] # running weight orientation, position
|
||||
weight: [2000,500000.0,30,50]
|
||||
vec_convergence: [0.0,0.0] # orientation, position, orientation metric activation, position metric activation
|
||||
terminal: True
|
||||
run_weight: 0.0 #0.05
|
||||
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: [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,500000.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
|
||||
run_weight: 0.0
|
||||
run_weight: 0.001
|
||||
use_metric: True
|
||||
|
||||
|
||||
cspace_cfg:
|
||||
weight: 10000.0
|
||||
terminal: True
|
||||
@@ -54,7 +55,7 @@ cost:
|
||||
|
||||
bound_cfg:
|
||||
weight: [5000.0, 50000.0, 50000.0, 50000.0] # needs to be 3 values
|
||||
smooth_weight: [0.0,2000.0, 50.0, 0.0] # [vel, acc, jerk,]
|
||||
smooth_weight: [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
|
||||
@@ -78,11 +79,11 @@ cost:
|
||||
|
||||
|
||||
lbfgs:
|
||||
n_iters: 400
|
||||
n_iters: 400 # 400
|
||||
inner_iters: 25
|
||||
cold_start_n_iters: 200
|
||||
cold_start_n_iters: null
|
||||
min_iters: 25
|
||||
line_search_scale: [0.01, 0.3,0.7,1.0] # #
|
||||
line_search_scale: [0.01, 0.3, 0.7,1.0] # #
|
||||
fixed_iters: True
|
||||
cost_convergence: 0.01
|
||||
cost_delta_threshold: 1.0
|
||||
@@ -90,7 +91,7 @@ lbfgs:
|
||||
epsilon: 0.01
|
||||
history: 15 #15
|
||||
use_cuda_graph: True
|
||||
n_envs: 1
|
||||
n_problems: 1
|
||||
store_debug: False
|
||||
use_cuda_kernel: True
|
||||
stable_mode: True
|
||||
|
||||
109
src/curobo/content/configs/task/finetune_trajopt_slow.yml
Normal file
109
src/curobo/content/configs/task/finetune_trajopt_slow.yml
Normal file
@@ -0,0 +1,109 @@
|
||||
|
||||
##
|
||||
## 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,500000.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
|
||||
run_weight: 0.0 #0.05
|
||||
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: [1.00,1.00,1.00,1.0,1.0,1.0] # running weight orientation, position
|
||||
weight: [2000,500000.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
|
||||
run_weight: 0.001
|
||||
use_metric: True
|
||||
|
||||
|
||||
cspace_cfg:
|
||||
weight: 10000.0
|
||||
terminal: True
|
||||
run_weight: 0.00 #1
|
||||
|
||||
bound_cfg:
|
||||
weight: [5000.0, 50000.0, 50000.0, 50000.0] # needs to be 3 values
|
||||
|
||||
smooth_weight: [0.0,50000.0, 500.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
|
||||
null_space_weight: [0.0]
|
||||
|
||||
primitive_collision_cfg:
|
||||
weight: 1000000.0
|
||||
use_sweep: True
|
||||
sweep_steps: 6
|
||||
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 # 400
|
||||
inner_iters: 25
|
||||
cold_start_n_iters: 200
|
||||
min_iters: 25
|
||||
line_search_scale: [0.01, 0.3, 0.7,1.0] # #
|
||||
fixed_iters: True
|
||||
cost_convergence: 0.01
|
||||
cost_delta_threshold: 1.0
|
||||
cost_relative_threshold: 0.999 #0.999
|
||||
epsilon: 0.01
|
||||
history: 15 #15
|
||||
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'
|
||||
@@ -32,6 +32,7 @@ cost:
|
||||
vec_convergence: [0.0, 0.00]
|
||||
terminal: False
|
||||
use_metric: True
|
||||
run_weight: 1.0
|
||||
link_pose_cfg:
|
||||
vec_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
|
||||
weight: [1000, 20000, 30, 50]
|
||||
@@ -58,7 +59,7 @@ cost:
|
||||
lbfgs:
|
||||
n_iters: 100 #60
|
||||
inner_iters: 25
|
||||
cold_start_n_iters: 100
|
||||
cold_start_n_iters: null
|
||||
min_iters: 20
|
||||
line_search_scale: [0.01, 0.3, 0.7, 1.0]
|
||||
fixed_iters: True
|
||||
@@ -69,7 +70,7 @@ lbfgs:
|
||||
history: 6
|
||||
horizon: 1
|
||||
use_cuda_graph: True
|
||||
n_envs: 1
|
||||
n_problems: 1
|
||||
store_debug: False
|
||||
use_cuda_kernel: True
|
||||
stable_mode: True
|
||||
|
||||
@@ -83,7 +83,7 @@ lbfgs:
|
||||
epsilon: 0.01
|
||||
history: 15 #15
|
||||
use_cuda_graph: True
|
||||
n_envs: 1
|
||||
n_problems: 1
|
||||
store_debug: False
|
||||
use_cuda_kernel: True
|
||||
stable_mode: True
|
||||
|
||||
@@ -31,11 +31,11 @@ model:
|
||||
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
|
||||
run_vec_weight: [0.00,0.00,0.00,0.0,0.0,0.0] # running weight orientation, position
|
||||
weight: [2000,50000.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: 0.00
|
||||
run_weight: 1.0
|
||||
use_metric: True
|
||||
|
||||
link_pose_cfg:
|
||||
@@ -44,7 +44,7 @@ cost:
|
||||
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
|
||||
run_weight: 0.0
|
||||
run_weight: 0.001
|
||||
use_metric: True
|
||||
|
||||
cspace_cfg:
|
||||
@@ -54,7 +54,9 @@ 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
|
||||
@@ -79,9 +81,9 @@ cost:
|
||||
|
||||
|
||||
lbfgs:
|
||||
n_iters: 175 #175
|
||||
n_iters: 125 #175
|
||||
inner_iters: 25
|
||||
cold_start_n_iters: 150
|
||||
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] #
|
||||
fixed_iters: True
|
||||
@@ -91,7 +93,7 @@ lbfgs:
|
||||
epsilon: 0.01
|
||||
history: 15
|
||||
use_cuda_graph: True
|
||||
n_envs: 1
|
||||
n_problems: 1
|
||||
store_debug: False
|
||||
use_cuda_kernel: True
|
||||
stable_mode: True
|
||||
|
||||
@@ -31,6 +31,7 @@ cost:
|
||||
vec_convergence: [0.00, 0.000] # orientation, position
|
||||
terminal: False
|
||||
use_metric: True
|
||||
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]
|
||||
@@ -56,7 +57,7 @@ mppi:
|
||||
init_cov : 1.0 #0.15 #.5 #.5
|
||||
gamma : 1.0
|
||||
n_iters : 4
|
||||
cold_start_n_iters: 4
|
||||
cold_start_n_iters: null
|
||||
step_size_mean : 0.9
|
||||
step_size_cov : 0.1
|
||||
beta : 0.01
|
||||
@@ -69,12 +70,12 @@ mppi:
|
||||
sample_mode : 'BEST'
|
||||
base_action : 'REPEAT'
|
||||
squash_fn : 'CLAMP'
|
||||
n_envs : 1
|
||||
n_problems : 1
|
||||
use_cuda_graph : True
|
||||
seed : 0
|
||||
store_debug : False
|
||||
random_mean : False
|
||||
sample_per_env : True
|
||||
sample_per_problem: True
|
||||
sync_cuda_time : False
|
||||
use_coo_sparse : True
|
||||
sample_params:
|
||||
|
||||
@@ -89,12 +89,12 @@ mppi:
|
||||
sample_mode : 'BEST'
|
||||
base_action : 'REPEAT'
|
||||
squash_fn : 'CLAMP'
|
||||
n_envs : 1
|
||||
n_problems : 1
|
||||
use_cuda_graph : True
|
||||
seed : 0
|
||||
store_debug : False
|
||||
random_mean : True
|
||||
sample_per_env : False
|
||||
sample_per_problem: False
|
||||
sync_cuda_time : True
|
||||
use_coo_sparse : True
|
||||
sample_params:
|
||||
|
||||
@@ -30,17 +30,17 @@ model:
|
||||
cost:
|
||||
pose_cfg:
|
||||
vec_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
|
||||
run_vec_weight: [1.0,1.0,1.0,1.0,1.0,1.0] # running weight
|
||||
run_vec_weight: [0.0,0.0,0.0,0.0,0.0,0.0] # running weight
|
||||
weight: [250.0, 5000.0, 20, 20]
|
||||
vec_convergence: [0.0,0.0,1000.0,1000.0]
|
||||
terminal: True
|
||||
run_weight: 0.00
|
||||
run_weight: 1.0
|
||||
use_metric: True
|
||||
|
||||
link_pose_cfg:
|
||||
vec_weight: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
|
||||
run_vec_weight: [1.0,1.0,1.0,1.0,1.0,1.0] # running weight
|
||||
weight: [250.0, 5000.0, 40, 40]
|
||||
run_vec_weight: [0.00,0.00,0.00,0.0,0.0,0.0] # running weight orientation, position
|
||||
weight: [0.0, 5000.0, 40, 40]
|
||||
vec_convergence: [0.0,0.0,1000.0,1000.0]
|
||||
terminal: True
|
||||
run_weight: 0.00
|
||||
@@ -54,10 +54,12 @@ cost:
|
||||
bound_cfg:
|
||||
weight: [0.1, 0.1,0.0,0.0]
|
||||
activation_distance: [0.0,0.0,0.0,0.0] #-#0.01
|
||||
#smooth_weight: [0.0,100.0,1.0,0.0]
|
||||
smooth_weight: [0.0,20.0,0.0,0.0]
|
||||
run_weight_velocity: 0.0
|
||||
run_weight_acceleration: 1.0
|
||||
run_weight_jerk: 1.0
|
||||
null_space_weight: [0.00]
|
||||
|
||||
primitive_collision_cfg:
|
||||
weight: 5000.0
|
||||
@@ -80,7 +82,7 @@ mppi:
|
||||
init_cov : 0.5
|
||||
gamma : 1.0
|
||||
n_iters : 2
|
||||
cold_start_n_iters: 2
|
||||
cold_start_n_iters: null
|
||||
step_size_mean : 0.9
|
||||
step_size_cov : 0.01
|
||||
beta : 0.01
|
||||
@@ -93,12 +95,12 @@ mppi:
|
||||
sample_mode : 'BEST'
|
||||
base_action : 'REPEAT'
|
||||
squash_fn : 'CLAMP'
|
||||
n_envs : 1
|
||||
n_problems : 1
|
||||
use_cuda_graph : True
|
||||
seed : 0
|
||||
store_debug : False
|
||||
random_mean : True
|
||||
sample_per_env : True
|
||||
sample_per_problem: True
|
||||
sync_cuda_time : False
|
||||
use_coo_sparse : True
|
||||
sample_params:
|
||||
|
||||
@@ -11,4 +11,4 @@
|
||||
cuboid:
|
||||
table:
|
||||
dims: [5.0, 5.0, 0.2] # x, y, z
|
||||
pose: [0.0, 0.0, -0.1, 1, 0, 0, 0.0] # x, y, z, qx, qy, qz, qw
|
||||
pose: [0.0, 0.0, -0.1, 1, 0, 0, 0.0] # x, y, z, qx, qy, qz, qw
|
||||
Reference in New Issue
Block a user