-
Notifications
You must be signed in to change notification settings - Fork 8
/
Copy pathmission.launch.py
156 lines (134 loc) · 5.08 KB
/
mission.launch.py
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
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import IncludeLaunchDescription
from launch.conditions import LaunchConfigurationEquals
from launch.conditions import LaunchConfigurationNotEquals
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
adaptation_manager = LaunchConfiguration('adaptation_manager')
mission_type = LaunchConfiguration('mission_type')
result_filename = LaunchConfiguration('result_filename')
battery_constraint = LaunchConfiguration('battery_constraint')
battery_constraint_value = LaunchConfiguration('battery_constraint_value')
mc_reasoning_time_filename = LaunchConfiguration('mc_reasoning_time_filename')
adaptation_manager_arg = DeclareLaunchArgument(
'adaptation_manager',
default_value='none',
description='Adaptation manager in charge' +
'[none or metacontrol or random]'
)
mission_type_arg = DeclareLaunchArgument(
'mission_type',
default_value='time_constrained_mission',
description='Desired mission type' +
'[time_constrained_mission or const_dist_mission]'
)
result_filename_arg = DeclareLaunchArgument(
'result_filename',
default_value='',
description='Name of the results file'
)
battery_constraint_arg = DeclareLaunchArgument(
'battery_constraint',
default_value='False',
description='Desired battery functionality' +
'[True or False]'
)
battery_constraint_value_arg = DeclareLaunchArgument(
'battery_constraint_value',
default_value='0.2',
description='battery constraint value'
)
mc_reasoning_time_filename_arg = DeclareLaunchArgument(
'mc_reasoning_time_filename',
default_value='metacontrol_reasoning_time',
description='metacontrol reasoning time filename'
)
pkg_suave_path = get_package_share_directory(
'suave_missions')
mission_config = os.path.join(
get_package_share_directory('suave_missions'),
'config',
'mission_config.yaml'
)
mission_metrics_node = Node(
package='suave_metrics',
executable='mission_metrics',
name='mission_metrics',
parameters=[mission_config, {
'adaptation_manager': adaptation_manager,
'mission_name': mission_type,
}],
condition=LaunchConfigurationEquals('result_filename', '')
)
mission_metrics_node_override = Node(
package='suave_metrics',
executable='mission_metrics',
name='mission_metrics',
parameters=[mission_config, {
'adaptation_manager': adaptation_manager,
'mission_name': mission_type,
'result_filename': result_filename,
}],
condition=LaunchConfigurationNotEquals('result_filename', '')
)
mission_node = Node(
package='suave_missions',
executable=mission_type,
name='mission_node',
parameters=[
mission_config,
{
'battery_constraint': battery_constraint,
'battery_constraint_value': battery_constraint_value,
}],
)
pkg_suave_path = get_package_share_directory('suave')
suave_launch_path = os.path.join(
pkg_suave_path,
'launch',
'suave.launch.py'
)
pkg_suave_metacontrol_path = get_package_share_directory(
'suave_metacontrol')
suave_metacontrol_launch_path = os.path.join(
pkg_suave_metacontrol_path,
'launch',
'suave_metacontrol.launch.py'
)
pkg_suave_random_path = get_package_share_directory(
'suave_random')
suave_random_launch_path = os.path.join(
pkg_suave_random_path,
'launch',
'suave_random.launch.py'
)
suave_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(suave_launch_path),
condition=LaunchConfigurationEquals('adaptation_manager', 'none'))
suave_metacontrol_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(suave_metacontrol_launch_path),
launch_arguments = {
'reasoning_time_filename' : mc_reasoning_time_filename}.items(),
condition=LaunchConfigurationEquals(
'adaptation_manager', 'metacontrol'))
suave_random_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(suave_random_launch_path),
condition=LaunchConfigurationEquals('adaptation_manager', 'random'))
return LaunchDescription([
adaptation_manager_arg,
mission_type_arg,
result_filename_arg,
battery_constraint_arg,
battery_constraint_value_arg,
mission_metrics_node,
mission_metrics_node_override,
mission_node,
suave_launch,
suave_metacontrol_launch,
suave_random_launch,
])