2929#
3030# Author: Denis Stogl
3131
32- from launch_ros .actions import Node
33- from launch_ros .parameter_descriptions import ParameterFile
34- from launch_ros .substitutions import FindPackageShare
35-
3632from launch import LaunchDescription
37- from launch .actions import DeclareLaunchArgument , IncludeLaunchDescription
33+ from launch .actions import (
34+ DeclareLaunchArgument ,
35+ IncludeLaunchDescription ,
36+ OpaqueFunction ,
37+ )
3838from launch .conditions import IfCondition , UnlessCondition
39+ from launch .launch_description_sources import AnyLaunchDescriptionSource
3940from launch .substitutions import (
4041 AndSubstitution ,
4142 LaunchConfiguration ,
4243 NotSubstitution ,
4344 PathJoinSubstitution ,
4445)
45- from launch .launch_description_sources import AnyLaunchDescriptionSource
46+ from launch_ros .actions import Node
47+ from launch_ros .parameter_descriptions import ParameterFile
48+ from launch_ros .substitutions import FindPackageShare
4649
4750
48- def launch_setup ():
51+ def launch_setup (context ):
4952 # Initialize Arguments
5053 ur_type = LaunchConfiguration ("ur_type" )
5154 robot_ip = LaunchConfiguration ("robot_ip" )
@@ -164,41 +167,21 @@ def controller_spawner(controllers, active=True):
164167 "force_torque_sensor_broadcaster" ,
165168 ]
166169 controllers_inactive = [
170+ "scaled_joint_trajectory_controller" ,
171+ "joint_trajectory_controller" ,
172+ "forward_velocity_controller" ,
167173 "forward_position_controller" ,
168174 "passthrough_trajectory_controller" ,
169175 ]
176+ if activate_joint_controller .perform (context ) == "true" :
177+ controllers_active .append (initial_joint_controller .perform (context ))
178+ controllers_inactive .remove (initial_joint_controller .perform (context ))
170179
171- controller_spawners = [controller_spawner (controllers_active )] + [
172- controller_spawner (controllers_inactive , active = False )
180+ controller_spawners = [
181+ controller_spawner (controllers_active ),
182+ controller_spawner (controllers_inactive , active = False ),
173183 ]
174184
175- # There may be other controllers of the joints, but this is the initially-started one
176- initial_joint_controller_spawner_started = Node (
177- package = "controller_manager" ,
178- executable = "spawner" ,
179- arguments = [
180- initial_joint_controller ,
181- "-c" ,
182- "/controller_manager" ,
183- "--controller-manager-timeout" ,
184- controller_spawner_timeout ,
185- ],
186- condition = IfCondition (activate_joint_controller ),
187- )
188- initial_joint_controller_spawner_stopped = Node (
189- package = "controller_manager" ,
190- executable = "spawner" ,
191- arguments = [
192- initial_joint_controller ,
193- "-c" ,
194- "/controller_manager" ,
195- "--controller-manager-timeout" ,
196- controller_spawner_timeout ,
197- "--inactive" ,
198- ],
199- condition = UnlessCondition (activate_joint_controller ),
200- )
201-
202185 rsp = IncludeLaunchDescription (
203186 AnyLaunchDescriptionSource (description_launchfile ),
204187 launch_arguments = {
@@ -215,8 +198,6 @@ def controller_spawner(controllers, active=True):
215198 urscript_interface ,
216199 rsp ,
217200 rviz_node ,
218- initial_joint_controller_spawner_stopped ,
219- initial_joint_controller_spawner_started ,
220201 ] + controller_spawners
221202
222203 return nodes_to_start
@@ -331,6 +312,13 @@ def generate_launch_description():
331312 DeclareLaunchArgument (
332313 "initial_joint_controller" ,
333314 default_value = "scaled_joint_trajectory_controller" ,
315+ choices = [
316+ "scaled_joint_trajectory_controller" ,
317+ "joint_trajectory_controller" ,
318+ "forward_velocity_controller" ,
319+ "forward_position_controller" ,
320+ "passthrough_trajectory_controller" ,
321+ ],
334322 description = "Initially loaded robot controller." ,
335323 )
336324 )
@@ -482,4 +470,4 @@ def generate_launch_description():
482470 ],
483471 )
484472 )
485- return LaunchDescription (declared_arguments + launch_setup () )
473+ return LaunchDescription (declared_arguments + [ OpaqueFunction ( function = launch_setup )] )
0 commit comments