-
Notifications
You must be signed in to change notification settings - Fork 21
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Collision meshes for lbr iisy3 + planning config (#28)
* remeshed collision * add planning yamls * enforce_constrained_state_space * set traj visual to true in rviz config * add projection_evaluator --------- Co-authored-by: Svastits <svastits1@gmail.com> Co-authored-by: kovacsge11 <kovacsge11@gmail.com>
- Loading branch information
1 parent
aef5dbc
commit e01a07b
Showing
11 changed files
with
225 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,35 @@ | ||
planning_plugin: chomp_interface/CHOMPPlanner | ||
request_adapters: >- | ||
default_planner_request_adapters/AddTimeOptimalParameterization | ||
default_planner_request_adapters/FixWorkspaceBounds | ||
default_planner_request_adapters/FixStartStateBounds | ||
default_planner_request_adapters/FixStartStateCollision | ||
default_planner_request_adapters/FixStartStatePathConstraints | ||
start_state_max_bounds_error: 0.1 | ||
planning_time_limit: 10.0 | ||
max_iterations: 200 | ||
max_iterations_after_collision_free: 5 | ||
smoothness_cost_weight: 0.1 | ||
obstacle_cost_weight: 1.0 | ||
learning_rate: 0.01 | ||
animate_path: true | ||
add_randomness: false | ||
smoothness_cost_velocity: 0.0 | ||
smoothness_cost_acceleration: 1.0 | ||
smoothness_cost_jerk: 0.0 | ||
hmc_discretization: 0.01 | ||
hmc_stochasticity: 0.01 | ||
hmc_annealing_factor: 0.99 | ||
use_hamiltonian_monte_carlo: false | ||
ridge_factor: 0.0 | ||
use_pseudo_inverse: false | ||
pseudo_inverse_ridge_factor: 1e-4 | ||
animate_endeffector: false | ||
joint_update_limit: 0.1 | ||
collision_clearance: 0.2 | ||
collision_threshold: 0.07 | ||
random_jump_amount: 1.0 | ||
use_stochastic_descent: true | ||
enable_failure_recovery: false | ||
max_recovery_attempts: 5 | ||
trajectory_initialization_method: "quintic-spline" |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,172 @@ | ||
planning_plugin: ompl_interface/OMPLPlanner | ||
# To optionally use Ruckig for jerk-limited smoothing, add this line to the request adapters below | ||
# default_planner_request_adapters/AddRuckigTrajectorySmoothing | ||
request_adapters: >- | ||
default_planner_request_adapters/AddTimeOptimalParameterization | ||
default_planner_request_adapters/ResolveConstraintFrames | ||
default_planner_request_adapters/FixWorkspaceBounds | ||
default_planner_request_adapters/FixStartStateBounds | ||
default_planner_request_adapters/FixStartStateCollision | ||
default_planner_request_adapters/FixStartStatePathConstraints | ||
start_state_max_bounds_error: 0.1 | ||
planner_configs: | ||
APSConfigDefault: | ||
type: geometric::AnytimePathShortening | ||
shortcut: 1 # Attempt to shortcut all new solution paths | ||
hybridize: 1 # Compute hybrid solution trajectories | ||
max_hybrid_paths: 36 # Number of hybrid paths generated per iteration | ||
num_planners: 8 # The number of default planners to use for planning | ||
planners: "RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" | ||
SBLkConfigDefault: | ||
type: geometric::SBL | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
ESTkConfigDefault: | ||
type: geometric::EST | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 | ||
LBKPIECEkConfigDefault: | ||
type: geometric::LBKPIECE | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 | ||
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 | ||
BKPIECEkConfigDefault: | ||
type: geometric::BKPIECE | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 | ||
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 | ||
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 | ||
KPIECEkConfigDefault: | ||
type: geometric::KPIECE | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 | ||
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] | ||
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 | ||
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 | ||
RRTkConfigDefault: | ||
type: geometric::RRT | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 | ||
RRTConnectkConfigDefault: | ||
type: geometric::RRTConnect | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
RRTstarkConfigDefault: | ||
type: geometric::RRTstar | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 | ||
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 | ||
TRRTkConfigDefault: | ||
type: geometric::TRRT | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 | ||
max_states_failed: 10 # when to start increasing temp. default: 10 | ||
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 | ||
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 | ||
init_temperature: 10e-6 # initial temperature. default: 10e-6 | ||
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() | ||
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 | ||
k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() | ||
PRMkConfigDefault: | ||
type: geometric::PRM | ||
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 | ||
PRMstarkConfigDefault: | ||
type: geometric::PRMstar | ||
FMTkConfigDefault: | ||
type: geometric::FMT | ||
num_samples: 1000 # number of states that the planner should sample. default: 1000 | ||
radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 | ||
nearest_k: 1 # use Knearest strategy. default: 1 | ||
cache_cc: 1 # use collision checking cache. default: 1 | ||
heuristics: 0 # activate cost to go heuristics. default: 0 | ||
extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 | ||
BFMTkConfigDefault: | ||
type: geometric::BFMT | ||
num_samples: 1000 # number of states that the planner should sample. default: 1000 | ||
radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 | ||
nearest_k: 1 # use the Knearest strategy. default: 1 | ||
balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 | ||
optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 | ||
heuristics: 1 # activates cost to go heuristics. default: 1 | ||
cache_cc: 1 # use the collision checking cache. default: 1 | ||
extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 | ||
PDSTkConfigDefault: | ||
type: geometric::PDST | ||
STRIDEkConfigDefault: | ||
type: geometric::STRIDE | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 | ||
use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 | ||
degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 | ||
max_degree: 18 # max degree of a node in the GNAT. default: 12 | ||
min_degree: 12 # min degree of a node in the GNAT. default: 12 | ||
max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 | ||
estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 | ||
min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 | ||
BiTRRTkConfigDefault: | ||
type: geometric::BiTRRT | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 | ||
init_temperature: 100 # initial temperature. default: 100 | ||
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() | ||
frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 | ||
cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf | ||
LBTRRTkConfigDefault: | ||
type: geometric::LBTRRT | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 | ||
epsilon: 0.4 # optimality approximation factor. default: 0.4 | ||
BiESTkConfigDefault: | ||
type: geometric::BiEST | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
ProjESTkConfigDefault: | ||
type: geometric::ProjEST | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 | ||
LazyPRMkConfigDefault: | ||
type: geometric::LazyPRM | ||
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() | ||
LazyPRMstarkConfigDefault: | ||
type: geometric::LazyPRMstar | ||
SPARSkConfigDefault: | ||
type: geometric::SPARS | ||
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 | ||
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 | ||
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 | ||
max_failures: 1000 # maximum consecutive failure limit. default: 1000 | ||
SPARStwokConfigDefault: | ||
type: geometric::SPARStwo | ||
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 | ||
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 | ||
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 | ||
max_failures: 5000 # maximum consecutive failure limit. default: 5000 | ||
TrajOptDefault: | ||
type: geometric::TrajOpt | ||
|
||
lbr_iisy_arm: | ||
enforce_constrained_state_space: true | ||
projection_evaluator: joints(joint_a1,joint_a2) | ||
planner_configs: | ||
- APSConfigDefault | ||
- SBLkConfigDefault | ||
- ESTkConfigDefault | ||
- LBKPIECEkConfigDefault | ||
- BKPIECEkConfigDefault | ||
- KPIECEkConfigDefault | ||
- RRTkConfigDefault | ||
- RRTConnectkConfigDefault | ||
- RRTstarkConfigDefault | ||
- TRRTkConfigDefault | ||
- PRMkConfigDefault | ||
- PRMstarkConfigDefault | ||
- FMTkConfigDefault | ||
- BFMTkConfigDefault | ||
- PDSTkConfigDefault | ||
- STRIDEkConfigDefault | ||
- BiTRRTkConfigDefault | ||
- LBTRRTkConfigDefault | ||
- BiESTkConfigDefault | ||
- ProjESTkConfigDefault | ||
- LazyPRMkConfigDefault | ||
- LazyPRMstarkConfigDefault | ||
- SPARSkConfigDefault | ||
- SPARStwokConfigDefault | ||
- TrajOptDefault |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,17 @@ | ||
planning_plugin: stomp_moveit/StompPlanner | ||
request_adapters: >- | ||
default_planner_request_adapters/AddTimeOptimalParameterization | ||
default_planner_request_adapters/FixWorkspaceBounds | ||
default_planner_request_adapters/FixStartStateBounds | ||
default_planner_request_adapters/FixStartStateCollision | ||
default_planner_request_adapters/FixStartStatePathConstraints | ||
stomp_moveit: | ||
num_timesteps: 60 | ||
num_iterations: 40 | ||
num_iterations_after_valid: 0 | ||
num_rollouts: 30 | ||
max_rollouts: 30 | ||
exponentiated_cost_sensitivity: 0.5 | ||
control_cost_weight: 0.1 | ||
delta_t: 0.1 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Binary file modified
BIN
-434 KB
(28%)
kuka_lbr_iisy_support/meshes/LBRiisy3R760/collision/base_link.stl
Binary file not shown.
Binary file modified
BIN
+53.8 KB
(180%)
kuka_lbr_iisy_support/meshes/LBRiisy3R760/collision/link_1.stl
Binary file not shown.
Binary file modified
BIN
-129 KB
(47%)
kuka_lbr_iisy_support/meshes/LBRiisy3R760/collision/link_2.stl
Binary file not shown.
Binary file modified
BIN
+50.3 KB
(170%)
kuka_lbr_iisy_support/meshes/LBRiisy3R760/collision/link_3.stl
Binary file not shown.
Binary file modified
BIN
-117 KB
(50%)
kuka_lbr_iisy_support/meshes/LBRiisy3R760/collision/link_4.stl
Binary file not shown.
Binary file modified
BIN
+2.05 KB
(100%)
kuka_lbr_iisy_support/meshes/LBRiisy3R760/collision/link_5.stl
Binary file not shown.
Binary file modified
BIN
-1.35 MB
(4.5%)
kuka_lbr_iisy_support/meshes/LBRiisy3R760/collision/link_6.stl
Binary file not shown.