54
54
from launch .substitutions import EnvironmentVariable
55
55
from launch .substitutions import LaunchConfiguration
56
56
from launch .substitutions import AndSubstitution
57
- from launch .substitutions import OrSubstitution
58
57
from launch .substitutions import NotSubstitution
59
58
from launch .substitutions import PathJoinSubstitution
60
59
from launch .substitutions import PythonExpression
@@ -84,15 +83,30 @@ def generate_launch_description():
84
83
use_directional_indicator = LaunchConfiguration ('use_directional_indicator' )
85
84
vibrator_type = LaunchConfiguration ('vibrator_type' )
86
85
87
- # switch lidar node based on model_name
88
- use_velodyne = PythonExpression (['"' , model_name , '" in ["cabot3-s1"]' ])
89
- use_hesai = PythonExpression (['"' , model_name , '" in ["cabot3-ace2", "cabot3-i1", "cabot3-m1", "cabot3-m2", "cabot3-k1"]' ])
90
- use_lslidar = PythonExpression (['"' , model_name , '" in ["cabot3-k2"]' ])
91
- use_rslidar = PythonExpression (['"' , model_name , '" in ["cabot3-k3"]' ])
92
- use_velodyne = NotSubstitution (OrSubstitution (use_hesai , OrSubstitution (use_lslidar , use_rslidar )))
93
- use_can = PythonExpression (['"' , model_name , '" in ["cabot3-k1", "cabot3-k2", "cabot3-k3"]' ])
94
- use_serial = NotSubstitution (use_can )
95
- use_livox = PythonExpression (['"' , model_name , '" in ["cabot3-i1", "cabot3-m1", "cabot3-m2", "cabot3-k1", "cabot3-k2", "cabot3-k3"]' ])
86
+ # Define models with their associated flags (without the "use_" prefix)
87
+ model_flags = {
88
+ "cabot3-s1" : ["velodyne" , "serial" ],
89
+ "cabot3-ace2" : ["hesai" , "serial" ],
90
+ "cabot3-i1" : ["hesai" , "livox" , "serial" ],
91
+ "cabot3-m1" : ["hesai" , "livox" , "serial" ],
92
+ "cabot3-m2" : ["hesai" , "livox" , "serial" ],
93
+ "cabot3-k1" : ["hesai" , "livox" , "can" ],
94
+ "cabot3-k2" : ["lslidar" , "livox" , "can" ],
95
+ "cabot3-k3" : ["rslidar" , "livox" , "can" ],
96
+ }
97
+
98
+ # Helper function to check if a flag applies to the given model
99
+ def has_flag (flag_name ):
100
+ return PythonExpression (['"' , model_name , '" in ' , str ([k for k , v in model_flags .items () if flag_name in v ])])
101
+
102
+ # Flags derived from the model's features (using the "use_" prefix for variable names)
103
+ use_velodyne = has_flag ("velodyne" )
104
+ use_hesai = has_flag ("hesai" )
105
+ use_lslidar = has_flag ("lslidar" )
106
+ use_rslidar = has_flag ("rslidar" )
107
+ use_livox = has_flag ("livox" )
108
+ use_serial = has_flag ("serial" )
109
+ use_can = has_flag ("can" )
96
110
97
111
xacro_for_cabot_model = PathJoinSubstitution ([
98
112
get_package_share_directory ('cabot_description' ),
@@ -142,6 +156,19 @@ def generate_launch_description():
142
156
return LaunchDescription ([
143
157
# save all log file in the directory where the launch.log file is saved
144
158
SetEnvironmentVariable ('ROS_LOG_DIR' , launch_config .log_dir ),
159
+ DeclareLaunchArgument (
160
+ 'model' ,
161
+ default_value = EnvironmentVariable ('CABOT_MODEL' ),
162
+ description = 'CaBot model'
163
+ ),
164
+ LogInfo (msg = PythonExpression (["\" Launching for model: " , model_name , "\" " ])),
165
+ LogInfo (msg = PythonExpression (["\" use_velodyne: " , use_velodyne , "\" " ])),
166
+ LogInfo (msg = PythonExpression (["\" use_hesai: " , use_hesai , "\" " ])),
167
+ LogInfo (msg = PythonExpression (["\" use_lslidar: " , use_lslidar , "\" " ])),
168
+ LogInfo (msg = PythonExpression (["\" use_rslidar: " , use_rslidar , "\" " ])),
169
+ LogInfo (msg = PythonExpression (["\" use_livox: " , use_livox , "\" " ])),
170
+ LogInfo (msg = PythonExpression (["\" use_serial: " , use_serial , "\" " ])),
171
+ LogInfo (msg = PythonExpression (["\" use_can: " , use_can , "\" " ])),
145
172
DeclareLaunchArgument (
146
173
'use_sim_time' ,
147
174
default_value = 'false' ,
@@ -152,11 +179,6 @@ def generate_launch_description():
152
179
OnShutdown (on_shutdown = [AppendLogDirPrefix ("cabot_base" )]),
153
180
condition = UnlessCondition (use_sim_time )
154
181
),
155
- DeclareLaunchArgument (
156
- 'model' ,
157
- default_value = EnvironmentVariable ('CABOT_MODEL' ),
158
- description = 'CaBot model'
159
- ),
160
182
DeclareLaunchArgument (
161
183
'touch_params' ,
162
184
default_value = EnvironmentVariable ('CABOT_TOUCH_PARAMS' ),
0 commit comments