-
Notifications
You must be signed in to change notification settings - Fork 97
/
Copy pathfetch_bringup.launch
267 lines (237 loc) · 10.9 KB
/
fetch_bringup.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
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
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
<launch>
<arg name="hostname" default="fetch15" />
<arg name="launch_moveit" default="true" />
<arg name="launch_teleop" default="true" />
<arg name="launch_move_base" default="true" />
<arg name="launch_sound_play" default="true" />
<arg name="launch_insta360" default="true" />
<arg name="use_voice_text" default="true" />
<arg name="boot_sound" default="false" />
<arg name="map_frame" default="eng2" />
<arg name="map_file" default="$(find jsk_maps)/raw_maps/eng2-7f-0.05.yaml"/>
<arg name="keepout_map_file" default="$(find jsk_maps)/raw_maps/eng2-7f-0.05_keepout.yaml" />
<arg name="use_build_map" default="false" />
<arg name="use_keepout" default="true" />
<param name="robot/type" value="fetch" />
<param name="robot/name" command='bash -c "hostname | xargs echo -n"' />
<include file="$(find jsk_fetch_startup)/jsk_fetch.machine" />
<!-- add jsk startups -->
<node pkg="jsk_fetch_startup" name="battery_warning" type="battery_warning.py"
respawn="true" output="screen">
<rosparam>
duration: 180
charge_level_threshold: 80.0
shutdown_level_threshold: 60.0
charge_level_step: 10.0
volume: 1.0
</rosparam>
</node>
<node pkg="jsk_robot_startup" name="nav_speak" type="nav_speak.py" respawn="true" >
<rosparam>
lang: japanese
volume: 0.5
</rosparam>
</node>
<node if="$(arg boot_sound)" pkg="jsk_robot_startup" name="boot_sound" type="boot_sound.py" >
<param name="wav_file" value="$(find jsk_fetch_startup)/data/boot_sound.wav" />
<param name="preferred_interface" value="wlan0" />
</node>
<!-- look at human for Fetch -->
<node name="look_at_human"
pkg="jsk_fetch_startup" type="fetch-look-at-human.l" output="screen">
<remap from="~input/people_pose_array" to="/edgetpu_human_pose_estimator/output/poses"/>
</node>
<!-- insta360 air images -->
<include file="$(find jsk_fetch_startup)/launch/fetch_insta360_$(env ROS_DISTRO).launch"
if="$(arg launch_insta360)" />
<!-- english speach node -->
<!-- disable sound_play in julius.launch and place it in fetch_bringup.launch -->
<!-- see: https://github.com/jsk-ros-pkg/jsk_robot/pull/1140 -->
<node name="sound_play" pkg="sound_play" type="soundplay_node.py"
respawn="true" if="$(arg launch_sound_play)" />
<!-- japanese speech node -->
<include if="$(arg use_voice_text)" file="$(find voice_text)/launch/voice_text.launch">
<arg name="launch_sound_play" value="$(arg launch_sound_play)" />
<arg name="sound_play_respawn" value="true" />
</include>
<include unless="$(arg use_voice_text)" file="$(find aques_talk)/launch/aques_talk.launch">
<arg name="launch_sound_play" value="$(arg launch_sound_play)" />
<arg name="sound_play_respawn" value="true" />
</include>
<!-- Buffer Server -->
<node pkg="tf2_ros" type="buffer_server" name="tf2_buffer_server" output="screen">
<param name="buffer_size" value="120.0"/>
</node>
<!-- logging -->
<include file="$(find jsk_fetch_startup)/launch/fetch_lifelog.xml">
<arg name="map_frame" value="$(arg map_frame)" />
<arg name="vital_check" value="false" />
</include>
<!-- diagnostic aggregator -->
<node pkg="diagnostic_aggregator" type="aggregator_node"
name="diag_agg" args="CPP" output="screen" >
<rosparam command="load" file="$(find jsk_fetch_startup)/config/fetch_analyzers.yaml" />
</node>
<!-- publish CPU status to diagnostics -->
<node name="cpu_monitor" pkg="pr2_computer_monitor" type="cpu_monitor.py"
args="--diag-hostname=my_machine" >
<param name="check_ipmi_tool" value="false" type="bool" />
<param name="enforce_clock_speed" value="false" type="bool" />
<param name="num_cores" value="-1" type="int" />
<param name="load1_threshold" value="7.0"/>
<param name="load5_threshold" value="5.0"/>
</node>
<!-- twitter -->
<include file="$(find jsk_fetch_startup)/launch/fetch_tweet.launch" />
<!-- app manager -->
<include file="$(find jsk_robot_startup)/lifelog/app_manager.launch">
<arg name="use_applist" value="false" /> <!-- use plugin -->
<arg name="respawn" value="false" />
<arg name="basic" value="true" />
<arg name="basic_yaml" value="/var/lib/robot/roswww_basic_keys.yaml" />
</include>
<!-- downsample / throttle sensor data -->
<include file="$(find jsk_fetch_startup)/launch/fetch_sensors.xml" >
<arg name="launch_manager" value="false"/>
</include>
<!-- include fetch moveit -->
<group if="$(arg launch_moveit)">
<include file="$(find fetch_moveit_config)/launch/move_group.launch" />
<!-- overwrite fetch.srdf -->
<!-- The semantic description that corresponds to the URDF -->
<param name="robot_description_semantic"
command="rosrun xacro xacro --inorder $(find jsk_fetch_startup)/launch/moveit/fetch.srdf.xacro" />
</group>
<!-- teleop -->
<include file="$(find jsk_fetch_startup)/launch/fetch_teleop.xml"
if="$(arg launch_teleop)" >
<arg name="odom_topic" value="/odom_combined" />
</include>
<!-- network status -->
<node pkg="jsk_network_tools" type="network_status.py" name="network_status" />
<!-- network detector -->
<node pkg="pr2_computer_monitor" type="network_detector" name="network_detector">
<rosparam>
interface_name: wlan0
</rosparam>
</node>
<!-- speech recognition -->
<node name="respeaker_transformer" pkg="tf" type="static_transform_publisher"
args="0 0 0.1 0 0 0 head_pan_link respeaker_base 100"/>
<!-- disable sound_play in julius.launch and place it in fetch_bringup.launch -->
<!-- see: https://github.com/jsk-ros-pkg/jsk_robot/pull/1140 -->
<include file="$(find julius_ros)/launch/julius.launch">
<arg name="launch_audio_capture" value="false"/>
<arg name="launch_sound_play" value="false"/>
<arg name="speech_to_text_topic" value="speech_to_text_julius"/>
</include>
<include file="$(find respeaker_ros)/launch/sample_respeaker.launch">
<arg name="publish_tf" default="false"/>
<arg name="launch_soundplay" default="false"/>
<arg name="audio" value="speech_audio"/>
<arg name="speech_to_text" value="speech_to_text_google"/>
<arg name="language" value="ja-JP"/>
</include>
<!-- set fetch speak action server names -->
<!-- this parameter is for speech_to_text node in respeaker_ros -->
<!-- https://github.com/jsk-ros-pkg/jsk_3rdparty/pull/168 -->
<group ns="speech_to_text">
<rosparam>
tts_action_names:
- sound_play
- robotsound_jp
</rosparam>
</group>
<!-- select mux for selecting speech_to_text service -->
<!-- the mux node is in jsk_3rdparty/dialogflow_task_executive -->
<!-- https://github.com/jsk-ros-pkg/jsk_3rdparty/tree/master/dialogflow_task_executive -->
<node name="speech_to_text_selector" pkg="jsk_robot_startup" type="mux_selector.py"
respawn="true"
args="/network/connected 'm.data==False' /speech_to_text_julius">
<remap from="mux" to="speech_to_text_mux" />
<rosparam>
default_select: speech_to_text_google
patient: 6
</rosparam>
</node>
<group if="$(arg launch_move_base)">
<!-- jsk_maps -->
<include file="$(find jsk_maps)/launch/start_map_$(arg map_frame).launch">
<arg name="launch_map_server" value="true" />
<arg name="keepout" value="$(arg use_keepout)" />
</include>
<!-- dock localization -->
<node pkg="jsk_fetch_startup" type="correct_position.py" name="correct_position" respawn="true">
<rosparam>
vital_rate: 0.1
</rosparam>
</node>
<!-- include fetch_navigation -->
<include file="$(find fetch_navigation)/launch/fetch_nav.launch" unless="$(arg use_build_map)" >
<arg name="map_file" value="$(arg map_file)" />
<arg name="map_keepout_file" value="$(arg keepout_map_file)" />
<arg name="use_keepout" value="$(arg use_keepout)" />
<arg name="use_map_topic" value="true" />
<arg name="launch_map_server" value="false" />
<arg name="odom_topic" value="/odom_combined" />
</include>
<!-- relay plan path topic for visualization -->
<node name="relay_navfn_planner_plan"
pkg="topic_tools" type="relay"
args="/move_base/NavfnROS/plan /move_base/navigation_plan_viz" />
<node name="relay_global_planner_plan"
pkg="topic_tools" type="relay"
args="/move_base/GlobalPlanner/plan /move_base/navigation_plan_viz" />
<node name="relay_trajectory_planner_global_plan"
pkg="topic_tools" type="relay"
args="/move_base/TrajectoryPlannerROS/global_plan /move_base/global_plan_viz" />
<node name="relay_trajectory_planner_local_plan"
pkg="topic_tools" type="relay"
args="/move_base/TrajectoryPlannerROS/local_plan /move_base/local_plan_viz" />
<node name="relay_teb_planner_global_plan"
pkg="topic_tools" type="relay"
args="/move_base/TebLocalPlannerROS/global_plan /move_base/global_plan_viz" />
<node name="relay_teb_planner_local_plan"
pkg="topic_tools" type="relay"
args="/move_base/TebLocalPlannerROS/local_plan /move_base/local_plan_viz" />
<!-- load amcl params -->
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_amcl_common_params.yaml" />
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_amcl_$(env ROS_DISTRO)_params.yaml" />
<!-- load move_base params -->
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_move_base_common_params.yaml" />
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_move_base_$(env ROS_DISTRO)_params.yaml" />
</group>
<!-- slam for build a map -->
<node pkg="slam_karto" type="slam_karto" name="slam_karto"
output="screen" if="$(arg use_build_map)" >
<remap from="scan" to="base_scan"/>
</node>
<!-- check if room light is on -->
<node name="check_room_light" pkg="jsk_robot_startup" type="check_room_light.py">
<remap from="~input" to="/head_camera/rgb/image_raw" />
</node>
<!-- robot_pose_publisher for rwt_nav -->
<node name="robot_pose_publisher" pkg="robot_pose_publisher" type="robot_pose_publisher">
<rosparam>
map_frame: /map
base_frame: /base_link
</rosparam>
</node>
<!-- Check fetch's boards in a constant period -->
<node name="check_board_info" pkg="jsk_fetch_diagnosis" type="check_driver_boards.py" output="screen">
</node>
<!-- send email by rostopic -->
<node name="email_topic" pkg="jsk_robot_startup" type="email_topic.py" output="screen">
<rosparam>
email_info: /var/lib/robot/email_topic.yaml
</rosparam>
</node>
<!-- Two robots cannot use one rosserial device at the same time -->
<group if="$(eval hostname == 'fetch1075')">
<include file="$(find jsk_fetch_startup)/launch/fetch_rosserial.launch" />
</group>
</launch>