99from launch .event_handlers import OnProcessExit , OnProcessStart
1010from launch_ros .actions import Node
1111from ament_index_python .packages import get_package_share_directory
12+ from launch .actions import SetEnvironmentVariable
1213
1314
1415def load_file (package_name , file_path ):
@@ -35,6 +36,33 @@ def generate_launch_description():
3536 "warehouse_arm_harmonic.world"
3637 )
3738
39+ # =========================
40+ # GAZEBO ENV PATHS (CLAVE)
41+ # =========================
42+
43+ gz_ros2_control_path = "/home/ws/install/gz_ros2_control/lib"
44+ gz_link_attacher_path = "/home/ws/install/gz_link_attacher/lib"
45+
46+ gz_plugin_path = (
47+ gz_link_attacher_path + ":" +
48+ gz_ros2_control_path + ":" +
49+ "/opt/ros/humble/lib"
50+ )
51+
52+ print ("DEBUG GZ_SIM_SYSTEM_PLUGIN_PATH =" , gz_plugin_path )
53+
54+ set_gz_plugin_path = SetEnvironmentVariable (
55+ name = "GZ_SIM_SYSTEM_PLUGIN_PATH" ,
56+ value = gz_plugin_path
57+ )
58+
59+ existing_ld = os .environ .get ("LD_LIBRARY_PATH" , "" )
60+
61+ set_ld_library_path = SetEnvironmentVariable (
62+ name = "LD_LIBRARY_PATH" ,
63+ value = gz_plugin_path + ":/usr/lib/x86_64-linux-gnu:" + existing_ld
64+ )
65+
3866 gz = ExecuteProcess (
3967 cmd = ["gz" , "sim" , "-r" , "-s" , "-v" , "4" , world_path ],
4068 output = "both"
@@ -103,17 +131,28 @@ def generate_launch_description():
103131 parameters = [robot_description , {"use_sim_time" : True }],
104132 )
105133
134+ static_tf = Node (
135+ package = "tf2_ros" ,
136+ executable = "static_transform_publisher" ,
137+ arguments = ["0" , "0" , "0.9" , "0" , "0" , "0" , "world" , "base_link" ],
138+ output = "both" ,
139+ parameters = [{"use_sim_time" : True }],
140+ )
141+
106142 spawn_robot = Node (
107143 package = "ros_gz_sim" ,
108144 executable = "create" ,
109145 arguments = [
110- "-param " , "robot_description" ,
146+ "-topic " , "robot_description" ,
111147 "-name" , "ur5" ,
148+ "-allow_renaming" , "true" ,
112149 "-x" , "0.0" ,
113150 "-y" , "0.0" ,
114151 "-z" , "0.9" ,
152+ "-R" , "0.0" ,
153+ "-P" , "0.0" ,
154+ "-Y" , "0.0" ,
115155 ],
116- parameters = [robot_description ],
117156 output = "both" ,
118157 )
119158
@@ -267,9 +306,11 @@ def generate_launch_description():
267306 print (">>> LAUNCH: move_node configurado" )
268307
269308 return LaunchDescription ([
270-
309+ set_gz_plugin_path ,
310+ set_ld_library_path ,
271311 gz ,
272312 robot_state_publisher ,
313+ static_tf ,
273314 clock_bridge ,
274315 delayed_spawn ,
275316 #delayed_joint_state_broadcaster,
0 commit comments