Skip to content

Commit

Permalink
refactor selector into a singleton and more selection tools
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood committed Mar 31, 2016
1 parent 997be5e commit 35b07ce
Show file tree
Hide file tree
Showing 15 changed files with 638 additions and 203 deletions.
4 changes: 3 additions & 1 deletion rclpy/__init__.py.in
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,9 @@ del source_path

for __execfile in __execfiles:
with open(__execfile, 'r') as __fh:
exec(__fh.read())
__code_object = compile(__fh.read(), __execfile, 'exec')
exec(__code_object)
del __code_object
del __fh
del __execfile
del __execfiles
2 changes: 1 addition & 1 deletion rclpy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@
<exec_depend>ament_index_python</exec_depend>

<test_depend>ament_cmake_nose</test_depend>
<test_depend>ament_index_python</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>launch</test_depend>
<test_depend>std_msgs</test_depend>
<test_depend>rosidl_generator_py</test_depend>
<test_depend>rosidl_typesupport_opensplice_c</test_depend>
Expand Down
61 changes: 37 additions & 24 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,45 +12,61 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import logging
import os
import sys

from rclpy import selector
from rclpy.exceptions import InvalidRCLPYImplementation
from rclpy.impl import implementation_singleton
from rclpy.impl import rmw_implementation_tools
from rclpy.node import Node

_rclpy = None
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


def init(args):
global _rclpy
rclpy_rmw_env = os.getenv('RCLPY_IMPLEMENTATION')
if rclpy_rmw_env:
selector.select(rclpy_rmw_env)
_rclpy = selector.import_rmw_implementation()
def init(args=None):
rclpy_rmw_env = os.getenv('RCLPY_IMPLEMENTATION', None)
if rclpy_rmw_env is not None:
available_rmw_implementations = rmw_implementation_tools.get_rmw_implementations()
if rclpy_rmw_env not in available_rmw_implementations:
logger = logging.getLogger('rclpy')
logger.error(
"The rmw implementation specified in 'RCLPY_IMPLEMENTATION={0}', "
"is not one of the available implementations: {1}"
.format(rclpy_rmw_env, available_rmw_implementations)
)
raise InvalidRCLPYImplementation()
rmw_implementation_tools.select_rmw_implementation(rclpy_rmw_env)
# This line changes what is in "_rclpy" to be the rmw implementation module that was imported.
implementation_singleton.set_rclpy_implementation(
rmw_implementation_tools.import_rmw_implementation()
)

assert _rclpy is not None, 'Could not load any RMW implementation'
return _rclpy.rclpy_init(args)
# Now we can use _rclpy to call the implementation specific rclpy_init().
return _rclpy.rclpy_init(args if args is not None else sys.argv)


def create_node(node_name):
node_handle = _rclpy.rclpy_create_node(node_name)
return Node(node_handle)


def spin(node):
def spin_once(node):
wait_set = _rclpy.rclpy_get_zero_initialized_wait_set()

_rclpy.rclpy_wait_set_init(wait_set, len(node.subscriptions), 0, 0)

while ok():
_rclpy.rclpy_wait_set_clear_subscriptions(wait_set)
for subscription in node.subscriptions:
_rclpy.rclpy_wait_set_add_subscription(wait_set, subscription.subscription_handle)
_rclpy.rclpy_wait(wait_set)
_rclpy.rclpy_wait_set_clear_subscriptions(wait_set)
for subscription in node.subscriptions:
_rclpy.rclpy_wait_set_add_subscription(wait_set, subscription.subscription_handle)

msg = _rclpy.rclpy_take(subscription.subscription_handle, subscription.msg_type)
_rclpy.rclpy_wait(wait_set)

if msg:
subscription.callback(msg)
# TODO(wjwwood): properly implement this by checking the contents of the wait_set.
for subscription in node.subscriptions:
msg = _rclpy.rclpy_take(subscription.subscription_handle, subscription.msg_type)
if msg:
subscription.callback(msg)


def ok():
Expand All @@ -61,8 +77,5 @@ def shutdown():
return _rclpy.rclpy_shutdown()


def get_implementation_identifier():
if _rclpy:
return _rclpy.rclpy_get_implementation_identifier()
else:
return None
def get_rmw_implementation_identifier():
return _rclpy.rclpy_get_rmw_implementation_identifier()
34 changes: 34 additions & 0 deletions rclpy/rclpy/exceptions.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.


class NotInitializedException(Exception):
"""Raised when the rclpy implementation is accessed before rclpy.init()."""

def __init__(self, *args):
Exception.__init__(self, 'rclpy.init() has not been called', *args)


class ImplementationAlreadyImportedException(Exception):
"""Raised on select_rmw_implemenation() after import_rmw_implementation() has been called."""

def __init__(self, *args):
Exception.__init__(self, 'rmw implementation already imported', *args)


class InvalidRCLPYImplementation(Exception):
"""Raised when an invalid RCLPYImplementation is requested."""

def __init__(self, *args):
Exception.__init__(self, 'requested invalid rmw implementation', *args)
Empty file added rclpy/rclpy/impl/__init__.py
Empty file.
65 changes: 65 additions & 0 deletions rclpy/rclpy/impl/implementation_singleton.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Provide singleton access to the rclpy implementation.
The singleton is called ``rclpy_implementation`` and is in this module.
For example, you might use it like this:
.. code::
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
_rclpy.rclpy_init()
while _rclpy.rclpy_ok():
# ...
Before you call :py:func:`rclpy.init` this singleton will point to an instance
of the :py:class:`ImplementationPlaceholder` class, which will raise a
:py:class:`rclpy.exceptions.NotInitializedException` when ever accessed.
After initialization it will point to the rclpy implementation C module.
"""

from rclpy.exceptions import NotInitializedException
from rclpy.impl.object_proxy import ObjectProxy


class ImplementationPlaceholder:
"""Placeholder for the rclpy implementation module.
This class will raise a :py:class:`NotInitializedException` when used.
"""

def __getattr__(self, key):
if key in ['__repr__']:
return object.__getattr__(key)
raise NotInitializedException()

rclpy_implementation = ObjectProxy(ImplementationPlaceholder())


def set_rclpy_implementation(implementation):
"""Set the rclpy implementation singleton."""
# Update the ObjectProxy to point to the rmw implementation specific module.
rclpy_implementation.__actual__ = implementation


def rclpy_implementation_is_placeholder(implementation=None):
"""Return True if the implementation is a placeholder, else False.
:param implementation: implementation to check, defaults to the singleton
:returns: bool
"""
implementation = rclpy_implementation if implementation is None else implementation
return isinstance(implementation, ImplementationPlaceholder)
165 changes: 165 additions & 0 deletions rclpy/rclpy/impl/object_proxy.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Provides an Object proxy that allows the underlying class to change."""

import ast
import inspect

# Inspired from:
# https://pypi.python.org/pypi/ProxyTypes (PSF/ZPL license)


class AbstractProxy(object):
"""Delegates all operations (except .__actual__) to another object."""

__slots__ = ()

def __call__(self, *args, **kw):
return self.__actual__(*args, **kw)

def __getattribute__(self, attr):
subject = object.__getattribute__(self, '__actual__')
if attr == '__actual__':
return subject
return getattr(subject, attr)

def __setattr__(self, attr, val):
if attr == '__actual__':
object.__setattr__(self, attr, val)
else:
setattr(self.__actual__, attr, val)

def __delattr__(self, attr):
if attr == '__actual__':
object.__delattr__(self, attr)
else:
delattr(self.__actual__, attr)

def __nonzero__(self):
return bool(self.__actual__)

def __getitem__(self, arg):
return self.__actual__[arg]

def __setitem__(self, arg, val):
self.__actual__[arg] = val

def __delitem__(self, arg):
del self.__actual__[arg]

def __getslice__(self, i, j):
return self.__actual__[i:j]

def __setslice__(self, i, j, val):
self.__actual__[i:j] = val

def __delslice__(self, i, j):
del self.__actual__[i:j]

def __contains__(self, ob):
return ob in self.__actual__

for name in [
'repr', 'str', 'hash', 'len', 'abs', 'complex', 'int', 'long', 'float',
'iter', 'oct', 'hex'
]:
code_object = compile(
'def __{0}__(self): return {0}(self.__actual__)'.format(name),
__file__,
'exec',
ast.PyCF_ONLY_AST,
)
ast.increment_lineno(code_object, inspect.getframeinfo(inspect.currentframe()).lineno - 6)
exec(compile(code_object, __file__, 'exec'))

for name in ['cmp', 'coerce', 'divmod']:
code_object = compile(
'def __{0}__(self, ob): return {0}(self.__actual__, ob)'.format(name),
__file__,
'exec',
ast.PyCF_ONLY_AST,
)
ast.increment_lineno(code_object, inspect.getframeinfo(inspect.currentframe()).lineno - 6)
exec(compile(code_object, __file__, 'exec'))

for name, op in [
('lt', '<'), ('gt', '>'), ('le', '<='), ('ge', '>='), ('eq', '=='), ('ne', '!=')
]:
code_object = compile(
'def __{0}__(self, ob): return self.__actual__ {1} ob'.format(name, op),
__file__,
'exec',
ast.PyCF_ONLY_AST,
)
ast.increment_lineno(code_object, inspect.getframeinfo(inspect.currentframe()).lineno - 6)
exec(compile(code_object, __file__, 'exec'))

for name, op in [('neg', '-'), ('pos', '+'), ('invert', '~')]:
code_object = compile(
'def __{0}__(self): return {1} self.__actual__'.format(name, op),
__file__,
'exec',
ast.PyCF_ONLY_AST,
)
ast.increment_lineno(code_object, inspect.getframeinfo(inspect.currentframe()).lineno - 6)
exec(compile(code_object, __file__, 'exec'))

for name, op in [
('or', '|'), ('and', '&'), ('xor', '^'), ('lshift', '<<'), ('rshift', '>>'),
('add', '+'), ('sub', '-'), ('mul', '*'), ('div', '/'), ('mod', '%'),
('truediv', '/'), ('floordiv', '//')
]:
code_object = compile(
"""
def __{name}__(self,ob):
return self.__actual__ {op} ob
def __r{name}__(self,ob):
return ob {op} self.__actual__
def __i{name}__(self,ob):
self.__actual__ {op}=ob
return self
""".format(name=name, op=op),
__file__,
'exec',
ast.PyCF_ONLY_AST,
)
ast.increment_lineno(code_object, inspect.getframeinfo(inspect.currentframe()).lineno - 6)
exec(compile(code_object, __file__, 'exec'))

del name, op

def __rdivmod__(self, ob):
return divmod(ob, self.__actual__)

def __pow__(self, *args):
return pow(self.__actual__, *args)

def __ipow__(self, ob):
self.__actual__ **= ob
return self

def __rpow__(self, ob):
return pow(ob, self.__actual__)


class ObjectProxy(AbstractProxy):
"""Proxy for an internally stored object."""

__slots__ = '__actual__'

def __init__(self, subject):
self.__actual__ = subject
Loading

0 comments on commit 35b07ce

Please sign in to comment.