@@ -173,20 +173,20 @@ def __init__(
173
173
if setup_assistant_file .exists ():
174
174
setup_assistant_yaml = load_yaml (setup_assistant_file )
175
175
config = setup_assistant_yaml .get ("moveit_setup_assistant_config" , {})
176
- urdf_config = config .get ("urdf" , config .get ("URDF" ))
177
- if urdf_config and self .__urdf_package is None :
178
- self .__urdf_package = Path (
179
- get_package_share_directory (urdf_config ["package" ])
180
- )
181
- self .__urdf_file_path = Path (urdf_config ["relative_path" ])
182
176
183
- if (xacro_args := urdf_config .get ("xacro_args" )) is not None :
177
+ if urdf_config := config .get ("urdf" , config .get ("URDF" )):
178
+ if self .__urdf_package is None :
179
+ self .__urdf_package = Path (
180
+ get_package_share_directory (urdf_config ["package" ])
181
+ )
182
+ self .__urdf_file_path = Path (urdf_config ["relative_path" ])
183
+
184
+ if xacro_args := urdf_config .get ("xacro_args" ):
184
185
self .__urdf_xacro_args = dict (
185
186
arg .split (":=" ) for arg in xacro_args .split (" " ) if arg
186
187
)
187
188
188
- srdf_config = config .get ("srdf" , config .get ("SRDF" ))
189
- if srdf_config :
189
+ if srdf_config := config .get ("srdf" , config .get ("SRDF" )):
190
190
self .__srdf_file_path = Path (srdf_config ["relative_path" ])
191
191
192
192
if not self .__urdf_package or not self .__urdf_file_path :
0 commit comments