roslaunch: #2560 <remap> from/to validation

This commit is contained in:
Ken Conley 2010-04-28 00:56:08 +00:00
parent e91c067eb7
commit c72a322119
9 changed files with 67 additions and 4 deletions

View File

@ -837,6 +837,8 @@ class TestXmlLoader(unittest.TestCase):
def test_remap_invalid(self):
tests = ['test-remap-invalid-1.xml',
'test-remap-invalid-2.xml',
'test-remap-invalid-name-from.xml',
'test-remap-invalid-name-to.xml',
]
loader = roslaunch.xmlloader.XmlLoader()
for filename in tests:

View File

@ -0,0 +1,6 @@
<launch>
<arg name="grounded" value="1"/>
<arg name="grounded" value="regrounded"/>
</launch>

View File

@ -0,0 +1,5 @@
<launch>
<arg name="invalid" value="$(arg missing)"/>
</launch>

View File

@ -0,0 +1,6 @@
<launch>
<group if="1" unless="1">
</group>
</launch>

View File

@ -0,0 +1,30 @@
<launch>
<group if="1">
<param name="group_if_pass" value="1" />
</group>
<group if="0">
<param name="group_if_fail" value="1" />
</group>
<group unless="0">
<param name="group_unless_pass" value="1" />
</group>
<group unless="1">
<param name="group_unless_fail" value="1" />
</group>
<param name="param_if_pass" value="1" if="1" />
<param name="param_if_fail" value="1" if="0" />
<param name="param_unless_pass" value="1" unless="0" />
<param name="param_unless_fail" value="1" unless="1" />
<remap from="from_if_pass" to="to_if_pass" if="1" />
<remap from="from_if_fail" to="to_if_fail" if="0" />
<remap from="from_unless_pass" to="to_unless_pass" unless="0" />
<remap from="from_unless_fail" to="to_unless_fail" unless="1" />
<node name="remap" pkg="test_ros" type="talker.py" />
</launch>

View File

@ -0,0 +1,3 @@
<launch>
<remap from="from something" to="to" />
</launch>

View File

@ -0,0 +1,3 @@
<launch>
<remap from="from" to="to something" />
</launch>

View File

@ -42,7 +42,7 @@ import os
import sys
from copy import deepcopy
from roslib.names import make_global_ns, ns_join, PRIV_NAME, load_mappings
from roslib.names import make_global_ns, ns_join, PRIV_NAME, load_mappings, is_legal_name
from roslaunch.core import Param, Master, RosbinExecutable, Node, Test, Machine, \
RLException, PHASE_SETUP
@ -204,6 +204,11 @@ class LoaderContext(object):
@param remap: remap setting
@type remap: (str, str)
"""
if not is_legal_name(remap[0]):
raise RLException("remap from [%s] is not a valid ROS name"%remap[0])
if not is_legal_name(remap[1]):
raise RLException("remap to [%s] is not a valid ROS name"%remap[1])
matches = [r for r in self._remap_args if r[0] == remap[0]]
for m in matches:
self._remap_args.remove(m)

View File

@ -634,9 +634,12 @@ class XmlLoader(roslaunch.loader.Loader):
elif name == 'param':
self._param_tag(tag, context, ros_config, verbose=verbose)
elif name == 'remap':
r = self._remap_tag(tag, context, ros_config)
if r is not None:
context.add_remap(r)
try:
r = self._remap_tag(tag, context, ros_config)
if r is not None:
context.add_remap(r)
except RLException, e:
raise XmlParseException("Invalid <remap> tag: %s.\nXML is %s"%(str(e), tag.toxml()))
elif name == 'machine':
val = self._machine_tag(tag, context, ros_config, verbose=verbose)
if val is not None: