66from launch .substitutions import LaunchConfiguration , PathJoinSubstitution
77from launch .conditions import IfCondition
88
9+
910def generate_launch_description ():
1011 package_name = 'elevation_mapping_cupy'
1112 share_dir = get_package_share_directory (package_name )
1213
1314 # Define paths
14- core_param_path = os .path .join (share_dir , 'config' , 'core' , 'core_param.yaml' )
15+ core_param_path = os .path .join (
16+ share_dir , 'config' , 'core' , 'core_param.yaml' )
1517
1618 # Declare launch arguments
1719 robot_param_arg = DeclareLaunchArgument (
1820 'robot_config' ,
1921 # default_value='turtle_bot/turle_bot_simple.yaml',
2022 default_value = 'menzi/base.yaml' ,
21- description = 'Name of the robot-specific config file within config/setups/'
23+ description = 'Name of the robot-specific config file within '
24+ 'config/setups/'
2225 )
2326
2427 launch_rviz_arg = DeclareLaunchArgument (
@@ -35,20 +38,22 @@ def generate_launch_description():
3538
3639 use_sim_time_arg = DeclareLaunchArgument (
3740 'use_sim_time' ,
38- default_value = 'false ' ,
41+ default_value = 'true ' ,
3942 description = 'Use simulation clock if true'
4043 )
4144
4245 # Get launch configurations
4346 robot_config = LaunchConfiguration ('robot_config' )
44- robot_param_path = PathJoinSubstitution ([share_dir , 'config' , 'setups' , robot_config ])
47+ robot_param_path = PathJoinSubstitution (
48+ [share_dir , 'config' , 'setups' , robot_config ])
4549 launch_rviz = LaunchConfiguration ('launch_rviz' )
4650 rviz_config = LaunchConfiguration ('rviz_config' )
4751 use_sim_time = LaunchConfiguration ('use_sim_time' )
4852
4953 # Verify core config exists
5054 if not os .path .exists (core_param_path ):
51- raise FileNotFoundError (f"Config file { core_param_path } does not exist" )
55+ raise FileNotFoundError (
56+ f"Config file { core_param_path } does not exist" )
5257
5358 # Define nodes
5459 elevation_mapping_node = Node (
0 commit comments