Skip to content

Commit 652913c

Browse files
committed
configured parking_space_detection.yaml for offline rosbag replay
Added parking_space_detection.yaml for offline rosbag replay. Note: This currently duplicates cone_detection.yaml and does not include any parking space detection logic.
1 parent e6d555b commit 652913c

1 file changed

Lines changed: 130 additions & 0 deletions

File tree

Lines changed: 130 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,130 @@
1+
description: "Run the yielding trajectory planner on the real vehicle with real perception"
2+
mode: hardware
3+
vehicle_interface: gem_hardware.GEMHardwareInterface
4+
mission_execution: StandardExecutor
5+
6+
# Recovery behavior after a component failure
7+
recovery:
8+
planning:
9+
trajectory_tracking : recovery.StopTrajectoryTracker
10+
11+
# Driving behavior for the GEM vehicle. Runs real pedestrian perception, yield planner, but does not send commands to real vehicle.
12+
drive:
13+
perception:
14+
state_estimation : GNSSStateEstimator
15+
obstacle_detection :
16+
type: cone_detection.ConeDetector3D
17+
args:
18+
camera_name: front #[front, front_right]
19+
camera_calib_file: ./GEMstack/knowledge/calibration/cameras.yaml
20+
enable_tracking: True # True if you want to enable tracking
21+
visualize_2d: False # True to see 2D detection visualization
22+
use_cyl_roi: False # True to use a cylinder ROI
23+
save_data: False # True to save sensor input data
24+
orientation: True # True to detect flipped cones
25+
use_start_frame: True # True to output in START frame
26+
27+
perception_normalization : StandardPerceptionNormalizer
28+
planning:
29+
relations_estimation:
30+
type: pedestrian_yield_logic.PedestrianYielder
31+
args:
32+
mode: 'real'
33+
params: {
34+
'yielder': 'expert', # 'expert', 'analytic', or 'simulation'
35+
'planner': 'milestone', # 'milestone', 'dt', or 'dx'
36+
'desired_speed': 1.0, # m/s, 1.5 m/s seems max speed? Feb24
37+
'acceleration': 0.75 # m/s2, 0.5 is not enough to start moving. Feb24
38+
}
39+
route_planning:
40+
type: StaticRoutePlanner
41+
args: [!relative_path '../GEMstack/knowledge/routes/forward_15m.csv','start']
42+
motion_planning: longitudinal_planning.YieldTrajectoryPlanner
43+
trajectory_tracking:
44+
type: pure_pursuit.PurePursuitTrajectoryTracker
45+
print: False
46+
47+
48+
log:
49+
# Specify the top-level folder to save the log files. Default is 'logs'
50+
#folder : 'logs'
51+
# If prefix is specified, then the log folder will be named with the prefix followed by the date and time. Default no prefix
52+
#prefix : 'fixed_route_'
53+
# If suffix is specified, then logs will output to folder/prefix+suffix. Default uses date and time as the suffix
54+
#suffix : 'test3'
55+
# Specify which ros topics to record to vehicle.bag. Default records nothing. This records the "standard" ROS topics.
56+
ros_topics :
57+
# Specify options to pass to rosbag record. Default is no options.
58+
#rosbag_options : '--split --size=1024'
59+
# If True, then record all readings / commands of the vehicle interface. Default False
60+
vehicle_interface : True
61+
# Specify which components to record to behavior.json. Default records nothing
62+
components : ['state_estimation','obstacle_detection','motion_planning']
63+
# Specify which components of state to record to state.json. Default records nothing
64+
#state: ['all']
65+
# Specify the rate in Hz at which to record state to state.json. Default records at the pipeline's rate
66+
#state_rate: 10
67+
# If True, then make plots of the recorded data specifically from PurePursuitTrajectoryTracker_debug.csv and report metrics. Default False
68+
#auto_plot : True
69+
replay: # Add items here to set certain topics / inputs to be replayed from logs
70+
# Specify which log folder to replay from
71+
log: /Users/aavideora/Documents/GitHub/GEMstack/logs/l1
72+
ros_topics : [camera_fl_arena_camera_node_image_raw]
73+
components : []
74+
75+
#usually can keep this constant
76+
computation_graph: !include "../GEMstack/knowledge/defaults/computation_graph.yaml"
77+
78+
variants:
79+
detector_only:
80+
run:
81+
description: "Run the pedestrian detection code"
82+
drive:
83+
planning:
84+
trajectory_tracking:
85+
real_sim:
86+
run:
87+
description: "Run the pedestrian detection code with real detection and fake simulation"
88+
mode: hardware
89+
vehicle_interface:
90+
type: gem_mixed.GEMRealSensorsWithSimMotionInterface
91+
args:
92+
scene: !relative_path '../scenes/xyhead_demo.yaml'
93+
mission_execution: StandardExecutor
94+
require_engaged: False
95+
visualization: !include "klampt_visualization.yaml"
96+
drive:
97+
perception:
98+
state_estimation : OmniscientStateEstimator
99+
planning:
100+
relations_estimation:
101+
type: pedestrian_yield_logic.PedestrianYielder
102+
args:
103+
mode: 'sim'
104+
105+
fake_real:
106+
run:
107+
description: "Run the yielding trajectory planner on the real vehicle with faked perception"
108+
drive:
109+
perception:
110+
obstacle_detection : cone_detection.FakeConeDetector2D
111+
112+
fake_sim:
113+
run:
114+
description: "Run the yielding trajectory planner in simulation with faked perception"
115+
mode: simulation
116+
vehicle_interface:
117+
type: gem_simulator.GEMDoubleIntegratorSimulationInterface
118+
args:
119+
scene: !relative_path '../scenes/xyhead_demo.yaml'
120+
visualization: !include "klampt_visualization.yaml"
121+
drive:
122+
perception:
123+
# agent_detection : pedestrian_detection.FakePedestrianDetector2D
124+
agent_detection : OmniscientAgentDetector #this option reads agents from the simulator
125+
state_estimation : OmniscientStateEstimator
126+
planning:
127+
relations_estimation:
128+
type: pedestrian_yield_logic.PedestrianYielder
129+
args:
130+
mode: 'sim'

0 commit comments

Comments
 (0)