1313# and limitations under the License.
1414#
1515# SPDX-License-Identifier: Apache-2.0
16-
16+ import tempfile
1717from ament_index_python .packages import get_package_share_directory
1818
1919from launch import LaunchDescription
20- from launch .actions import DeclareLaunchArgument
20+ from launch .actions import DeclareLaunchArgument , ExecuteProcess
2121from launch .substitutions import LaunchConfiguration
2222from launch .substitutions .path_join_substitution import PathJoinSubstitution
2323
2929
3030 DeclareLaunchArgument ('world_name' , default_value = 'default' ,
3131 description = 'World name' ),
32+
33+ DeclareLaunchArgument ('update_rate' , default_value = '5' ,
34+ description = 'Update rate of the sensor' ),
35+
36+ DeclareLaunchArgument ('image_width' , default_value = '320' ,
37+ description = 'Width of camera image' ),
38+
39+ DeclareLaunchArgument ('image_height' , default_value = '240' ,
40+ description = 'Height of camera image' ),
3241]
3342
3443for pose_element in ['x' , 'y' , 'z' , 'roll' , 'pitch' , 'yaw' ]:
@@ -41,10 +50,17 @@ def generate_launch_description():
4150
4251 camera_name = LaunchConfiguration ('camera_name' )
4352 world_name = LaunchConfiguration ('world_name' )
53+ update_rate = LaunchConfiguration ('update_rate' )
54+ image_width = LaunchConfiguration ('image_width' )
55+ image_height = LaunchConfiguration ('image_height' )
56+ camera_sdf = tempfile .NamedTemporaryFile (prefix = 'gazebo_static_camera_' , suffix = '.sdf' , delete = False )
4457
4558 x , y , z = LaunchConfiguration ('x' ), LaunchConfiguration ('y' ), LaunchConfiguration ('z' )
4659 roll , pitch , yaw = LaunchConfiguration ('roll' ), LaunchConfiguration ('pitch' ), LaunchConfiguration ('yaw' )
4760
61+ camera_sdf_xacro = ExecuteProcess (
62+ cmd = ['xacro' , '-o' , camera_sdf .name , ['update_rate:=' , update_rate ], ['image_width:=' , image_width ], ['image_height:=' , image_height ], PathJoinSubstitution ([gazebo_static_camera_dir , 'models' , 'camera.sdf.xacro' ])])
63+
4864 camera_bridge = Node (
4965 package = 'ros_gz_bridge' ,
5066 executable = 'parameter_bridge' ,
@@ -80,11 +96,12 @@ def generate_launch_description():
8096 '-R' , roll ,
8197 '-P' , pitch ,
8298 '-Y' , yaw ,
83- '-file' , PathJoinSubstitution ([ gazebo_static_camera_dir , 'models' , 'camera.sdf' ]) ],
99+ '-file' , camera_sdf . name ],
84100 output = 'screen'
85101 )
86102
87103 ld = LaunchDescription (ARGUMENTS )
104+ ld .add_action (camera_sdf_xacro )
88105 ld .add_action (camera_bridge )
89106 ld .add_action (spawn_camera )
90107 return ld
0 commit comments