-
Notifications
You must be signed in to change notification settings - Fork 3
/
config_lqg.yaml
142 lines (98 loc) · 3.54 KB
/
config_lqg.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
# Global seed for the RNG (-1 => random seed will be generated)
seed: -1
# Number of cores used for parallel path construction and evaluation
num_cores: 8
# Verbose output
verbose: False
# The path to the robot model file
robot_file: model/test_3dof.urdf
# The path to the environment file
environment_file: environment/env_3dof.xml
# The number of goal states generated by IK
num_generated_goal_states: 1
# Number of paths which have to be generated by RRT to evaluate
num_generated_paths: 500
# Timeout to generate 1 path (in seconds)
path_timeout: 100.0
# For the simplest toy problem. Use a linear path between the start and goal state
use_linear_path: False
# Number of simulation runs for the best found path
num_simulation_runs: 500
# Maximum angular velocity of the joints for the kinematic problem (in rad/sec)
max_velocity: 4.0
# The joint control rate
control_rate: 30.0
# The initial joint angles (has to be consistent with the number of links)
start_state: [0.7, 0.0, 1.5, 0.0, 0.0, 0.0]
#start_state: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
#start_state: [0.0, -1.57079632679489661923, 0.0, 0.0]
#Number of bins for the histograms
num_bins: 201
#################################################
## Uncertainty parameters
#################################################
# The error variables are defined as the standard deviation in percentage of the value range
# The minimum joint state covariance
min_process_covariance: 0.0
# The maximum joint state covariance
max_process_covariance: 5.0
# The minimum observation covariance
min_observation_covariance: 2.55
# The maximum observation covariance
max_observation_covariance: 5.0
#Determines which parameter (process covariance or observation
#covariance should be increased during simulation)
inc_covariance: process
# The number of covariance steps
covariance_steps: 5
path_deviation_cost: 200.0
control_deviation_cost: 1.0
################################################
## Reward parameters
################################################
# Reward params
discount_factor: 0.999999
# Penalty for crashing into an obstacle
illegal_move_penalty: 500.0
# Penalty for taking a step
step_penalty: 1.0
# Reward for reaching a terminal state
exit_reward: 1000.0
################################################
# The number of samples drawn from the distribution at each state to check a path for collision
sample_size: 1000
# Enforce the position and velocity constraints
enforce_constraints: True
# Enforce the control constraints
enforce_control_constraints: True
# Stop executing the path when state is terminal
stop_when_terminal: True
# Plot the paths generated by RRTConnect (should be 'False' for a large number of paths)
plot_paths: False
#Planning algorithm
planning_algorithm: RRTConnect
continuous_collision_check: True
#########################################
# Dynamic problem parameters
#########################################
dynamic_problem: True
gravity: 9.81
acceleration_limit: 100.0
simulation_step_size: 0.001
# Control sampler to use. 'discrete' or 'continuous'
control_sampler: discrete
# Number of controls to sample at the nearest node in the RRT tree
num_control_samples: 1
min_control_duration: 1
max_control_duration: 4
# The RRT goal bias
rrt_goal_bias: 0.05
#Determines if intermediate states along motions have to be added
#to the RRT tree (DON'T SET TO FALSE YET)
add_intermediate_states: True
#########################################
# Visualization
#########################################
show_viewer_evaluation: False
show_viewer_simulation: False
knows_collision: True