Bases: builtins.object
An abstract object. All components in MORSE (either physical components like actuators or sensors or pseudo components like component overlays) inherit from AbstractObject.
This abstract class provides all RPC service-related mechanics.
This method must be invoked by the component when a service completes.
Calling this method triggers the notification of task completion to the client.
Parameters: |
|
---|
This method is automatically invoked by the component when a service is interrupted, basically to notify to the client that the task has been interrupted.
It can be overriden in each component to provide a true interrupt, for exemple resseting the speed command to 0.0.
If you override it, do not forget to call self.completed with status.PREEMPTED.
When a task is considered ‘completed’ (the semantic of ‘completed’ is left to each component), the default_action method is expected to call this callback (if not None) with the task status (from core.status.*) + optional return value as a tuple.
For instance:
self.on_completion((status.FAILED, "Couldn't reach the target"))
self.on_completion((status.SUCCESS, {'x':1.0, 'y':0.54}))
self.on_completion((status.SUCCESS))
Bases: morse.core.object.Object
Basic Class for all actuator objects.
Provides common attributes.
Apply speed parameter to the parent robot
Parameters: | kind (string) – the kind of control to apply. Can be one of |
---|
[‘Position’, ‘Velocity’]. :param list linear_speed: the list of linear speed to apply, for each axis, in m/s. :param list angular_speed: the list of angular speed to apply, for each axis, in rad/s.
Bases: logging.StreamHandler
This module wraps the calls to the Blender Python API. This is intended for all the cases we need to run MORSE code outside Blender (mostly for documentation generation purposes).
Bases: morse.core.exceptions.MorseBuilderError
Morse Error caused by a mistyped method or object name in Builder.
Bases: morse.core.exceptions.MorseError
Morse Error caused by the Builder API.
Bases: morse.core.exceptions.MorseBuilderError
Morse Error caused by a wrong component in Builder.
Bases: morse.core.exceptions.MorseError
Morse Error triggered while manipulating MORSE environments (typically, wrong permissions on a file or inexistant environment).
Bases: morse.core.exceptions.MorseError
Morse Error caused by a Middleware.
Bases: morse.core.exceptions.MorseError
Morse Error caused by a Multinode configuration.
Bases: morse.core.exceptions.MorseError
Morse Error caused by a Service.
This module wraps the calls to the Blender ‘mathutils’ API. This is intended for all the cases we need to run MORSE code outside Blender (mostly for documentation generation purposes).
Bases: morse.core.abstractobject.AbstractObject
Basic Class for all 3D objects (components) used in the simulation. Provides common attributes.
Call the regular action function of the component.
Can be redefined in some of the subclases (sensor and actuator).
Base action performed by any object.
This method should be implemented by all subclasses that will be instanced (GPS, v_Omega, ATRV, etc.).
Bases: morse.core.abstractobject.AbstractObject
This class allows to define ‘overlay’. An ‘overlay’ is a pseudo component that masks a MORSE default component behind a custom facet (with for instance custom signatures for services, ports, etc.).
This is especially useful when integrating MORSE into an existing robotic architecture where components have custom services/ports/topics whose signature does not match MORSE defaults.
As of MORSE 0.4, only services can currently be overlaid.
When calling a component asynchronous service from an overlay, a callback (used to notify the client upon service completion) must be passed through. This callback does not usually appear in the service signature since it is added by the @async_service decorator.
Under normal circumstances, you must use this method as callback.
For instance, assume a Dummy component and an overlay MyDummy:
class Dummy(MorseObject):
@async_service
def dummy_service(self, arg1):
# Here, dummy_service has a callback parameter added
# by the decorator
pass
class MyDummy(MorseAbstractobject):
@async_service
def mydummy_service(self, arg1):
# [...do smthg useful]
# We call the overlaid asynchronous service
# 'dummy_service' by passing a special callback
# returned by 'self.chain_callback()'
self.overlaid_object.dummy_service(self.chain_callback(), arg1)
chain_callback takes a functor as an optional parameter. This functor is called after the (overlaid) service completion, but just before notifying the simulator client.
It can be used for output formatting for instance.
The functor must take one single parameter (a tuple (status, result)) and must as well return a tuple (status, result).
class MyDummy(MorseAbstractobject):
def mydummy_on_completion(self, result):
# This functor - here a simple function - simply
# format the result output.
# It could do anything else.
status, value = result
return (status, " . ".join(value))
@async_service
def mydummy_service(self, arg1):
self.overlaid_object.dummy_service(self.chain_callback(self.mydummy_on_completion), arg1)
Parameters: | fn – a functor to be called on service completion, before notifying the clients. Must have the following signature: (status, result) fn((status, result)) |
---|
Bases: builtins.object
Basic Class for all request dispatchers, i.e., classes that implement a request service.
Components can register such a service with the ‘register_service’ method. Please check its documentation for details.
To implement a concrete RequestManager (for a new middleware, for instance), the following methods must be overloaded:
- initialization(): perform here middleware specific initialization
- finalization(): perform here middleware specific finalization
- post_registration(): put here all middleware specific code that must be executed when a new service is registered.
- on_service_completion(): this method is called when a ‘long term’ request completes. You should implement here a way to notify your clients.
- main(): this method is called at each step of the simulation. You should read there incoming requests and write back results.
When a new request arrives, you must pass it to on_incoming_request() that dispatch or invoke properly the request.
Subclasses are also expected to overload the special __str__() method to provide middleware specific names.
This method will interrupt a running asynchronous service, uniquely described by its request_id
This method is meant to be overloaded by middlewares to perform specific finalizations.
Must return True is the finalization is successful, False in other cases.
This method is meant to be overloaded by middlewares to perform specific initializations.
Must return True is the initialization is successful, False in other cases.
This is the main method of the RequestManagerClass: it reads external incoming requests, dispatch them through the on_incoming_request() method, and write back answers.
Subclasses are expected to overload this method.
This method handles incoming requests: it figures out who registered the service, checks if the service returns immediately or must be started and only later checked for termination, invokes the service, and returns the service result (for service that returns immediately).
If something goes wrong while trying to call the method, a morse.core.exceptions.MorseRPCInvokationError is raised.
If everything goes well, the method return a tuple: (True, return_value) or (False, request_id). The first item tells if the service is a synchronous (short-term) service (value is True) or an asynchronous service (False).
For asynchronous services, the returned request id should allow to track the completion of the service. Upon completion, on_service_completion() is invoked.
This method is called when a asynchronous request completes.
Subclasses are expected to overload this method with code to notify the original request emitter.
Parameters: |
|
---|
This method is meant to be overloaded by middlewares that have specific initializations to do when a new service is exposed.
Parameters: |
|
---|---|
Returns: | True if the registration succeeded. |
Return type: | boolean |
This method is the one actually called from the MORSE main loop.
It simply updates the list of pending requests (if any) and calls the main processing method.
Allows a component to register an asynchronous RPC method.
A asynchronous method can last for several cycles without blocking the simulator. The callback method must take as first parameter a callable that must be used to set the results of the service upon completion.
For example, consider the following sample of asynchronous service:
def complex_computation(result_setter, param1, param2):
do_computation_step() #should stay short, but can last several simulation steps
if computation_done:
result_setter(computation_results)
request_manager.register_async_service("computer", complex_computation)
As soon as the ‘result_setter’ is called with the results of the service, the clients of this service are notified via their middlewares.
See register_service() for detailed documentation of parameters.
Allows a component to register a synchronous RPC method that is made publicly available to the outside world.
Parameters: |
|
---|
Bases: morse.core.object.Object
Basic Class for all robots
Inherits from the base object class.
Bases: morse.core.object.Object
Basic Class for all sensors
Inherits from the base object class.
Bases: builtins.object
Initializes and adds a new request manager from its name.
Parameters: | classpath (string) – the name (and path) of the Python class that implements the RequestManager interface (eg: ‘morse.middleware.socket_request_manager.SocketRequestManager’, ‘morse.middleware.yarp_request_manager.YarpRequestManager’,...). |
---|---|
Returns: | True if the request manager has been successfully loaded. |
Adds a mapping between a component and a request manager: all services exposed by this component are handled by this request manager.
A component may have 0, 1 or more request managers. if more than one, each request manager can independently invoke the service.
Parameters: |
|
---|
The @async_service decorator.
Refer to the @service decorator for most of the doc.
Asynchronous service specifics:
The @interruptible decorator.
Use this decorator to set an (asynchronous) service to be interruptible.
If MORSE receives a request for a new service while an interruptible service is running, the running service is preempted (the requester receives a morse.core.status.PREEMPTED status), and the new one is started.
See also noninterruptible() decorator.
The @noninterruptible decorator.
Use this decorator to set an (asynchronous) service to be non interruptible.
If MORSE receives a request for a new service while a non interruptible service is running, a failure message is returned to the requester.
See also interruptible() decorator.
The @service decorator.
This decorator can be used to automagically register a service in MORSE. Simply decorate the method you want to export as a RPC service with @service and MORSE automatically add and register it with the right middleware (depending on what is specified in the simulation configuration file).
This decorator works both with free function and for methods in classes inheriting from morse.core.object.Object. In the former case, you must specify a component (your service will belong to this namespace), in the later case, it is automatically set to the name of the corresponding MORSE component.
Parameters: |
|
---|
The request failed.
The request was interupted and replaced by another one
The request was successfully achieved
Bases: morse.core.wheeled_robot.PhysicsWheelRobot
Basic Class for robots using individual physics constraints
Inherits from the base robot class.
Attaches the wheel to the a-arm and then the a-arm to the body
Attaches a freely rotating wheel to the given parent using a 6DOF constraint. It can also rotate around the Z axis
Bases: morse.core.robot.Robot
Abstract base class for robots with wheels that turn as the robot moves. The wheels must be children of the robot in the Blender file.