-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathLoomo.launch
110 lines (90 loc) · 4.59 KB
/
Loomo.launch
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
<launch>
<!-- Explanation in the README.md file -->
<!-- GLOBAL PARAMETERS -->
<param name="ip_address" value="128.179.201.219" />
<!-- <param name="ip_address_neuro" value="192.168.0.152" /> -->
<!-- <param name="abs_path_to_tools" value="/home/theo/Autonomous_driving_pipeline/src/loomo/scripts/tools" /> -->
<param name="v_max" value="0.5" />
<param name="wheel_base" value="0.57" />
<param name="speed" value="0.5" />
<!-- PERCEPTION PARAMETERS: Default, Stark -->
<param name="PERCEPTION_FUNCTION" value="Default" />
<param name="mot_activated" value="False" />
<param name="model_perception_path" value="/home/theo/Autonomous_driving_pipeline/src/perception/scripts/Perception_Functions/saved_model.pth" />
<param name="dt_perception" value="0.2" />
<param name="downscale" value="2" />
<param name="detector_size" value="medium" />
<param name="tracking_confidence" value="0.9" />
<param name="visualization_percep" value="true" />
<param name="verbose_percep" type="int" value= "2" /> <!-- level of verbose 0 to 4-->
<!-- POSE ESTIMATION PARAMETERS: Default, VideoPose3D -->
<param name="POSE_ESTIMATION_FUNCTION" value="Default" />
<param name="keypoints_activated" value="True" />
<param name="dt_pose_estimation" value="0.2" />
<param name="visualization_3D_activated" value="True" />
<param name="keypoints_logging" value="false" />
<param name="save_keypoints_vid" value="True" />
<param name="verbose_keypoints" value="True" />
<!-- ROBOT STATE PARAMETERS: Default, EPFL_Driverless -->
<param name="ROBOT_STATE_FUNCTION" value="Default" />
<param name="dt_robot_state" value="0.02" />
<!-- MAP STATE PARAMETERS: Default -->
<param name="MAP_STATE_FUNCTION" value="Default" />
<param name="mapping_activated" value="True" />
<param name="map_state_activated" value="False" />
<param name="dt_map_state" value="0.2" />
<param name="verbose_map" value="True" />
<!-- PREDICTION PARAMETERS: Default, Trajnet -->
<param name="PREDICTION_FUNCTION" value="Default" />
<param name="prediction_activated" value="True" />
<param name="model_prediction_path" value="/home/theo/Autonomous_driving_pipeline/src/prediction/scripts/Prediction_Functions/models/lstm_directional_one_12_6_rerun.pkl" />
<param name="time_horizon_prediction" value="0.6" />
<param name="past_observations" value="3" />
<param name="dt_prediction" value="0.2" />
<!-- PATH PLANNING PARAMETERS: Default, Fake_Obst, CHUV -->
<param name="PATH_PLANNING_FUNCTION" value="CHUV" />
<param name="dt_path_planning" value="0.4" />
<param name="time_horizon_path_planning" value="1.2" />
<param name="planner_type" value="straight" />
<param name="robot_position" value="right" />
<param name="goal_x" value="3" />
<param name="goal_y" value="3" />
<param name="cyclic_goal" value="True" />
<param name="workarea_x_min" value="-2.0" />
<param name="workarea_x_max" value="5.0" />
<param name="workarea_y_min" value="-1.0" />
<param name="workarea_y_max" value="1.0" />
<param name="num_person" value="0" />
<!-- CONTROL PARAMETERS: Default, EPFL_Driverless -->
<param name="CONTROL_FUNCTION" value="Default" />
<param name="dt_control" value="0.25" />
<param name="time_horizon_control" value="1.2" />
<param name="n_states" value="3" />
<param name="verbose_ctrl" value="2" />
<!-- VISUALIZATION PARAMETERS: Default -->
<param name="visualization_activated" value="True" />
<param name="dt_visualization" value="0.4" />
<!-- PERCEPTION NODE -->
<node pkg="perception" type="perception.py" name="perception" output="screen">
</node>
<!-- POSE ESTIMATION NODE -->
<node pkg="pose_estimation" type="pose_estimation.py" name="pose_estimation" output="screen">
</node>
<!-- STATE ESTIMATION NODE -->
<node pkg="state_estimation" type="robot_state.py" name="robot_state" output="screen">
</node>
<node pkg="state_estimation" type="map_state.py" name="map_state" output="screen">
</node>
<!-- PREDICTION NODE -->
<node pkg="prediction" type="prediction.py" name="prediction" output="screen">
</node>
<!-- PLANNING NODE -->
<node pkg="path_planning" type="path_planning.py" name="path_planning" output="screen">
</node>
<!-- CONTROL NODE -->
<node pkg="control" type="control.py" name="control" output="screen">
</node>
<!-- VISUALIZATION NODE -->
<node pkg="visualization" type="visualization.py" name="visualization" output="screen">
</node>
</launch>