-
Notifications
You must be signed in to change notification settings - Fork 349
/
main.launch
116 lines (86 loc) · 4 KB
/
main.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
<launch>
<arg name="use_camera" default="false"/>
<arg name="use_arm" default="false"/>
<arg name="use_vslam" default="false"/>
<arg name="use_base" default="false"/>
<arg name="torque_control" default="false"/>
<arg name="use_sim" default="false"/>
<arg name="teleop" default="false"/>
<arg name="use_rviz" default="true"/>
<arg name="base" default="kobuki"/> <!-- Options: create and kobuki -->
<param name="use_camera" value="$(arg use_camera)"/>
<param name="use_arm" value="$(arg use_arm)"/>
<param name="use_vslam" value="$(arg use_vslam)"/>
<param name="use_sim" value="$(arg use_sim)"/>
<param name="use_base" value="$(arg use_base)"/>
<param name="torque_control" value="$(arg torque_control)"/>
<param name="teleop" value="$(arg teleop)"/>
<group unless="$(arg use_sim)">
<group if="$(arg use_camera)">
<include file="$(find realsense2_camera)/launch/rs_rgbd.launch">
<arg name="enable_pointcloud" value="false"/>
</include>
</group>
<group if="$(arg use_vslam)">
<group if="$(arg use_camera)">
<include file="$(find orb_slam2_ros)/launch/orb_slam2_realsense.launch">
<arg name="launch_realsense" value="false"/>
</include>
</group>
<group unless="$(arg use_camera)">
<include file="$(find orb_slam2_ros)/launch/orb_slam2_realsense.launch"/>
</group>
</group>
<group if="$(arg use_base)" >
<include file="$(find base_navigation)/launch/main_base.launch">
<arg name="base" value="$(arg base)"/>
</include>
</group>
<group if="$(arg teleop)">
<include file="$(find locobot_control)/launch/dynamixel_controllers.launch">
<arg name="dynamixel_info" value="$(find locobot_control)/config/dynamixels_teleop.yaml"/>
</include>
</group>
<group unless="$(arg teleop)">
<group if="$(eval arg('use_arm') or arg('use_camera') or arg('use_vslam'))">
<include file="$(find locobot_control)/launch/dynamixel_controllers.launch"/>
</group>
</group>
<node name="calibration_tf_broadcaster" pkg="locobot_calibration"
type="calibration_publish_transforms.py"/>
</group>
<!-- Gazebo -->
<group if="$(arg use_sim)">
<include file="$(find locobot_gazebo)/launch/gazebo_locobot.launch">
<arg name="base" value="$(arg base)"/>
</include>
<include file="$(find locobot_gazebo)/launch/gazebo_locobot_control.launch"/>
<node name="locobot_gazebo" pkg="locobot_gazebo" type="locobot_gazebo"
respawn="true" output="screen"/>
</group>
<!-- Common -->
<node name="turtlebot_controller_node" pkg="turtlebot_controller"
type="turtlebot_controller_node" output="screen"/>
<node name="gpmp_action_server" pkg="locobot_control"
type="pointrobot3factor_ros_server.py" output="screen"/>
<node name="pyrobot_kinematics" pkg="pyrobot_bridge"
type="kinematics.py"/>
<node name="pyrobot_moveit" pkg="pyrobot_bridge"
type="moveit_bridge.py"/>
<group if="$(eval arg('use_base') or arg('use_sim'))" >
<include file="$(find base_navigation)/launch/move_base.launch">
<arg name="use_map" value="$(arg use_vslam)"/>
<arg name="base" value="$(arg base)"/>
</include>
</group>
<group if="$(eval base =='create')">
<include file="$(find locobot_lite_moveit_config)/launch/demo.launch">
<arg name="use_rviz" value="$(arg use_rviz)"/>
</include>
</group>
<group if="$(eval base =='kobuki')">
<include file="$(find locobot_moveit_config)/launch/demo.launch">
<arg name="use_rviz" value="$(arg use_rviz)"/>
</include>
</group>
</launch>