From b44da295227d241e63dbd1551ef6cd7b8fdc22c2 Mon Sep 17 00:00:00 2001 From: ipa-nhg Date: Wed, 19 Nov 2025 14:47:20 +0100 Subject: [PATCH] Hot fix: Readme compiler is broken, the global parameters are defined as ros.Parameters and not RosParameters, they are the node-local parameters --- .../fraunhofer/ipa/rossystem/generator/READMECompiler.xtend | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/plugins/de.fraunhofer.ipa.rossystem.xtext/src/de/fraunhofer/ipa/rossystem/generator/READMECompiler.xtend b/plugins/de.fraunhofer.ipa.rossystem.xtext/src/de/fraunhofer/ipa/rossystem/generator/READMECompiler.xtend index a1d5b499..393c3173 100644 --- a/plugins/de.fraunhofer.ipa.rossystem.xtext/src/de/fraunhofer/ipa/rossystem/generator/READMECompiler.xtend +++ b/plugins/de.fraunhofer.ipa.rossystem.xtext/src/de/fraunhofer/ipa/rossystem/generator/READMECompiler.xtend @@ -10,7 +10,7 @@ import system.impl.RosServiceClientReferenceImpl import system.impl.RosServiceServerReferenceImpl import system.impl.RosSubscriberReferenceImpl import com.google.inject.Inject -import system.RosParameter +import ros.Parameter class READMECompiler { @@ -88,7 +88,7 @@ source install/setup.bash To execute the launch file, the following command can be called: ``` -ros2 launch «system.name» «system.name».launch.py «FOR param:system.parameter»«(param as RosParameter).name»:=«get_param_value((param as RosParameter).value,(param as RosParameter).name)» «ENDFOR» +ros2 launch «system.name» «system.name».launch.py «FOR param:system.parameter»«(param as ros.Parameter).name»:=«get_param_value((param as ros.Parameter).value,(param as ros.Parameter).name)» «ENDFOR» ``` The generated launch files requires the xterm package, it can be installed by: @@ -101,7 +101,7 @@ sudo apt install xterm To launch this system there is already an existing package that contains the launch file. It can be started by: ``` -ros2 launch «system.fromFile.split("/",2).get(0)» «system.fromFile.substring(system.fromFile.lastIndexOf('/') + 1)» «FOR param:system.parameter»«(param as RosParameter).name»:=«get_param_value((param as RosParameter).value,(param as RosParameter).name)» «ENDFOR» +ros2 launch «system.fromFile.split("/",2).get(0)» «system.fromFile.substring(system.fromFile.lastIndexOf('/') + 1)» «FOR param:system.parameter»«(param as ros.Parameter).name»:=«get_param_value((param as ros.Parameter).value,(param as ros.Parameter).name)» «ENDFOR» ``` «ENDIF»