1
+ from http .server import executable
2
+ from launch import LaunchDescription
3
+ from launch .actions import DeclareLaunchArgument , ExecuteProcess , RegisterEventHandler , IncludeLaunchDescription
4
+ from launch .substitutions import TextSubstitution , PathJoinSubstitution , LaunchConfiguration , Command
5
+ from launch_ros .actions import Node
6
+ from launch_ros .substitutions import FindPackageShare
7
+ from launch .launch_description_sources import PythonLaunchDescriptionSource
8
+ from launch .event_handlers import OnProcessExit , OnExecutionComplete
9
+ import os
10
+ from os import environ
11
+
12
+ from ament_index_python .packages import get_package_share_directory
13
+
14
+ import xacro
15
+
16
+
17
+ def generate_launch_description ():
18
+ mars_rover_demos_path = get_package_share_directory ('mars_rover' )
19
+ mars_rover_models_path = get_package_share_directory ('simulation' )
20
+
21
+ env = {'GZ_SIM_SYSTEM_PLUGIN_PATH' :
22
+ ':' .join ([environ .get ('GZ_SIM_SYSTEM_PLUGIN_PATH' , default = '' ),
23
+ environ .get ('LD_LIBRARY_PATH' , default = '' )]),
24
+ 'GZ_SIM_RESOURCE_PATH' :
25
+ ':' .join ([mars_rover_demos_path ])}
26
+
27
+ urdf_model_path = os .path .join (mars_rover_models_path , 'models' , 'curiosity_path' ,
28
+ 'urdf' , 'curiosity_mars_rover.xacro.urdf' )
29
+
30
+ doc = xacro .process_file (urdf_model_path )
31
+ robot_description = {'robot_description' : doc .toxml ()}
32
+
33
+ decalare_world_name_arg = DeclareLaunchArgument ('world_name' , default_value = 'mars_gale_crater_patch1.sdf' ,
34
+ description = 'Name of the world file to launch in Gazebo' )
35
+ world_name = LaunchConfiguration ('world_name' )
36
+
37
+ arm_node = Node (
38
+ package = "mars_rover" ,
39
+ executable = "move_arm" ,
40
+ output = 'screen'
41
+ )
42
+
43
+ mast_node = Node (
44
+ package = "mars_rover" ,
45
+ executable = "move_mast" ,
46
+ output = 'screen'
47
+ )
48
+
49
+ wheel_node = Node (
50
+ package = "mars_rover" ,
51
+ executable = "move_wheel" ,
52
+ output = 'screen'
53
+ )
54
+
55
+ run_node = Node (
56
+ package = "mars_rover" ,
57
+ executable = "run_demo" ,
58
+ output = 'screen'
59
+ )
60
+
61
+ start_world = ExecuteProcess (
62
+ cmd = ['gz sim' , world_name , '-r' ],
63
+ output = 'screen' ,
64
+ additional_env = env ,
65
+ shell = True
66
+ )
67
+
68
+ robot_state_publisher = Node (
69
+ package = 'robot_state_publisher' ,
70
+ executable = 'robot_state_publisher' ,
71
+ name = 'robot_state_publisher' ,
72
+ output = 'screen' ,
73
+ parameters = [robot_description ])
74
+
75
+ spawn = Node (
76
+ package = 'ros_gz_sim' , executable = 'create' ,
77
+ arguments = [
78
+ '-name' , 'curiosity_path' ,
79
+ '-topic' , robot_description ,
80
+ ],
81
+ output = 'screen'
82
+ )
83
+
84
+ ## Control Components
85
+
86
+ component_state_msg = '{name: "GazeboSimSystem", target_state: {id: 3, label: ""}}'
87
+
88
+ ## a hack to resolve current bug
89
+ set_hardware_interface_active = ExecuteProcess (
90
+ cmd = ['ros2' , 'service' , 'call' ,
91
+ 'controller_manager/set_hardware_component_state' ,
92
+ 'controller_manager_msgs/srv/SetHardwareComponentState' ,
93
+ component_state_msg ]
94
+ )
95
+
96
+ load_joint_state_broadcaster = ExecuteProcess (
97
+ cmd = ['ros2' , 'control' , 'load_controller' , '--set-state' , 'active' ,
98
+ 'joint_state_broadcaster' ],
99
+ output = 'screen'
100
+ )
101
+
102
+ load_arm_joint_traj_controller = ExecuteProcess (
103
+ cmd = ['ros2' , 'control' , 'load_controller' , '--set-state' , 'active' ,
104
+ 'arm_joint_trajectory_controller' ],
105
+ output = 'screen'
106
+ )
107
+
108
+ load_mast_joint_traj_controller = ExecuteProcess (
109
+ cmd = ['ros2' , 'control' , 'load_controller' , '--set-state' , 'active' ,
110
+ 'mast_joint_trajectory_controller' ],
111
+ output = 'screen'
112
+ )
113
+
114
+ load_wheel_joint_traj_controller = ExecuteProcess (
115
+ cmd = ['ros2' , 'control' , 'load_controller' , '--set-state' , 'active' ,
116
+ 'wheel_velocity_controller' ],
117
+ output = 'screen'
118
+ )
119
+
120
+ load_steer_joint_traj_controller = ExecuteProcess (
121
+ cmd = ['ros2' , 'control' , 'load_controller' , '--set-state' , 'active' ,
122
+ 'steer_position_controller' ],
123
+ output = 'screen'
124
+ )
125
+
126
+ load_suspension_joint_traj_controller = ExecuteProcess (
127
+ cmd = ['ros2' , 'control' , 'load_controller' , '--set-state' , 'active' ,
128
+ 'wheel_tree_position_controller' ],
129
+ output = 'screen'
130
+ )
131
+
132
+ return LaunchDescription ([
133
+ declare_world_name_arg ,
134
+ start_world ,
135
+ robot_state_publisher ,
136
+ spawn ,
137
+ arm_node ,
138
+ mast_node ,
139
+ wheel_node ,
140
+ run_node ,
141
+ RegisterEventHandler (
142
+ OnProcessExit (
143
+ target_action = spawn ,
144
+ on_exit = [set_hardware_interface_active ],
145
+ )
146
+ ),
147
+ RegisterEventHandler (
148
+ OnProcessExit (
149
+ target_action = set_hardware_interface_active ,
150
+ on_exit = [load_joint_state_broadcaster ],
151
+ )
152
+ ),
153
+ RegisterEventHandler (
154
+ OnProcessExit (
155
+ target_action = load_joint_state_broadcaster ,
156
+ on_exit = [load_arm_joint_traj_controller ,
157
+ load_mast_joint_traj_controller ,
158
+ load_wheel_joint_traj_controller ,
159
+ load_steer_joint_traj_controller ,
160
+ load_suspension_joint_traj_controller ],
161
+ )
162
+ ),
163
+ ])
0 commit comments