1818# flake8: noqa: F403,F405
1919import isaac_ros_launch_utils as lu
2020from isaac_ros_launch_utils .all_types import *
21-
22- # Camera config string is a subset of:
23- # - driver,rectify,resize,ess_full,ess_light,ess_skip_frames,cuvslam,nvblox
24- perceptor_configurations = {
25- 'front_configuration' : {
26- 'front_stereo_camera' : 'driver,rectify,resize,ess_full,cuvslam,nvblox' ,
27- 'back_stereo_camera' : '' ,
28- 'left_stereo_camera' : '' ,
29- 'right_stereo_camera' : '' ,
30- },
31- 'front_people_configuration' : {
32- 'front_stereo_camera' : 'driver,rectify,resize,ess_full,cuvslam,nvblox_people' ,
33- 'back_stereo_camera' : '' ,
34- 'left_stereo_camera' : '' ,
35- 'right_stereo_camera' : '' ,
36- },
37- 'front_left_right_configuration' : {
38- 'front_stereo_camera' : 'driver,rectify,resize,ess_full,cuvslam,nvblox' ,
39- 'back_stereo_camera' : '' ,
40- 'left_stereo_camera' : 'driver,rectify,resize,ess_light,ess_skip_frames,cuvslam,nvblox' ,
41- 'right_stereo_camera' : 'driver,rectify,resize,ess_light,ess_skip_frames,cuvslam,nvblox' ,
42- },
43- 'front_left_right_people_configuration' : {
44- 'front_stereo_camera' : 'driver,rectify,resize,ess_full,cuvslam,nvblox_people' ,
45- 'back_stereo_camera' : '' ,
46- 'left_stereo_camera' : 'driver,rectify,resize,ess_light,ess_skip_frames,cuvslam,nvblox' ,
47- 'right_stereo_camera' : 'driver,rectify,resize,ess_light,ess_skip_frames,cuvslam,nvblox' ,
48- },
49- }
21+ import isaac_ros_perceptor_python_utils .launch_utils as pu
5022
5123
5224def generate_launch_description () -> LaunchDescription :
5325 args = lu .ArgumentContainer ()
5426
5527 # String specifying the stereo camera configuration.
5628 args .add_arg ('stereo_camera_configuration' )
29+ args .add_arg ('nvblox_global_frame' , 'odom' )
30+ args .add_arg ('vslam_map_frame' , 'map' )
31+ args .add_arg ('vslam_odom_frame' , 'odom' )
32+ args .add_arg ('vslam_image_qos' )
33+ args .add_arg ('disable_cuvslam' , False )
34+ args .add_arg ('disable_nvblox' , False )
35+ args .add_arg ('disable_vgl' , True )
36+ args .add_arg ('nvblox_param_filename' , 'params/nvblox_perceptor.yaml' )
37+ args .add_arg ('nvblox_after_shutdown_map_save_path' , '' )
38+ args .add_arg ('is_sim' , False )
39+ actions = args .get_launch_actions ()
5740
58- perceptor_configuration = lu .get_dict_value (str (perceptor_configurations ),
59- args .stereo_camera_configuration )
41+ perceptor_configuration , loggings = pu .load_perceptor_configuration (
42+ args .stereo_camera_configuration , args .disable_cuvslam , args .disable_nvblox , args .disable_vgl )
43+ actions .extend (loggings )
6044
6145 enabled_stereo_cameras_drivers = lu .get_keys_with_substring_in_value (
6246 perceptor_configuration , 'driver' )
6347 enable_people_segmentation = lu .dict_values_contain_substring (perceptor_configuration ,
6448 'nvblox_people' )
6549
66- actions = args .get_launch_actions ()
6750 actions .append (
6851 lu .include (
6952 'nova_developer_kit_bringup' ,
@@ -78,7 +61,16 @@ def generate_launch_description() -> LaunchDescription:
7861 lu .include (
7962 'isaac_ros_perceptor_bringup' ,
8063 'launch/perceptor_general.launch.py' ,
81- launch_arguments = {'perceptor_configuration' : perceptor_configuration },
64+ launch_arguments = {
65+ 'perceptor_configuration' : perceptor_configuration ,
66+ 'nvblox_global_frame' : args .nvblox_global_frame ,
67+ 'vslam_odom_frame' : args .vslam_odom_frame ,
68+ 'vslam_map_frame' : args .vslam_map_frame ,
69+ 'nvblox_param_filename' : args .nvblox_param_filename ,
70+ 'nvblox_after_shutdown_map_save_path' : args .nvblox_after_shutdown_map_save_path ,
71+ 'vslam_image_qos' : args .vslam_image_qos ,
72+ 'is_sim' : args .is_sim ,
73+ },
8274 ))
8375
8476 return LaunchDescription (actions )
0 commit comments