morse.actuators package

Submodules

morse.actuators.armature module

class Armature(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

Armatures are the MORSE generic way to simulate kinematic chains made of a combination of revolute joints (hinge) and prismatic joints (slider).

This component only allows to set an armature configuration. To read the armature pose, you need an armature pose sensor.

Important

To be valid, special care must be given when creating armatures. If you want to add new one, please carefully read the armature creation documentation.

This actuator offers two main ways to control a kinematic chain: either by setting the values of each joint individually (via a continuous datastream or via dedicated services: translate(), set_translation(), rotate(), set_rotation()) or by placing the end-effector and relying on a inverse kinematic solver (via the services set_IK_target() and move_IK_target()).

Note

When setting the joints with a datastream, the data structure that the armature actuator expects depends on the armature itself. It is a dictionary of pair (joint name, joint value). Joint values are either radians (for revolute joints) or meters (for prismatic joints)

To use inverse kinematics, you must first define IK targets to control your kinematic chain. You can create them manually from Blender or directly in your Builder script (refer to the Examples section below for an example).

from morse.builder import *

robot = ATRV()

# imports an armature,
# either from a Blender file...
armature = Armature(model_name = "<blend file>")
# ...or by providing the name of an existing armature:
# armature = Armature(armature_name = "<name of armature>")
# (note that you can combine both options to select an armature in a 
# Blender file)

# if you want to use inverse kinematics, you can create 'IK targets'
# here as well:
armature.create_ik_targets(["<name of the bone you want to control>", ...])

# place your armature at the correct location
armature.translate(<x>, <y>, <z>)
armature.rotate(<rx>, <ry>, <rz>)

# define one or several communication interfaces, like 'socket' or 'ros'
# With ROS, this actuator exposes a JointTrajectoryAction interface.
armature.add_interface(<interface>)

robot.append(armature)

env = Environment('empty')

Note

ros Armatures can be controlled in ROS through the JointTrajectoryAction interface.

Sees:armature pose sensor
Noautoexample:
default_action()[source]

Move the armature according to both the value of local_data

find_dof(channel)[source]

Method that finds and returns the degree of freedom (dof) corresponding to the given channel. The dof has to be a blender_ik_setting. Returns a list [x,y,z] with the corresponding dofs as a boolean.

get_IK_limits(joint)[source]

Returns the IK limits for the given joint.

  • For revolute joints, returns a pair (ik_min,ik_max), in radians.
  • For prismatic joint, returns a pair (0.0, max translation), in meters.
get_dofs()[source]

Returns a dictionary with keys the channels of the armature and as values the rotation axes of the joint.

Rotation axes are represented as a list of boolean. For instance, [True, False, True] means that the x and z axes of the joint are free to rotate (or translate, depending on the type of the joint).

get_joints()[source]

Returns the names of all the joints in this armature, ordered from the root to the tip.

interrupt()[source]

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.

list_IK_targets()[source]
move_IK_target(callback, *param)

Moves an IK (inverse kinematic) target at a given speed (in m/s for translation, rad/s for rotation).

Note that moving an IK target conflicts somewhat with the original purpose of the inverse kinematic solver, and overall continuity is not guaranteed (the IK solver may find a solution for a given target position that ‘jumps’ relative to the solution for the previous target position).

Sees:

place_IK_target to set instantaneously the IK target pose.

Parameters:
  • name – name of the IK target (as returned by list_IK_targets())
  • translation – a [x,y,z] translation vector, in the scene frame,

in meters. :param rotation: a [rx,ry,rz] rotation, in the scene frame (ie, X,Y,Z rotation axis are the scene axis). Angles in radians. :param relative: if True (default), translation and rotation are relative to the current target pose. :param linear_speed: (default: value of the ik_target_linear_speed property) translation speed (in m/s). :param radial_speed: (default: value of the ik_target_radial_speed property) rotation speed (in rad/s).

place_IK_target(name, translation, euler_rotation=None, relative=True)[source]

Places instantaneously a IK (inverse kinematic) target to a given position and orientation.

Sees:move_IK_target to move the IK target over time.
Parameters:name – name of the IK target (as returned by

list_IK_targets()) :param translation: a [x,y,z] translation vector, in the scene frame, in meters. :param rotation: a [rx,ry,rz] rotation, in the scene frame (ie, X,Y,Z rotation axis are the scene axis). Angles in radians. :param relative: if True (default), translation and rotation are relative to the current target pose.

rotate(callback, *param)

Rotates a joint at a given speed (in rad/s).

Sees:

Blender documentation on joint rotation

Parameters:
  • joint – name of the armature’s joint to rotate
  • rotation – rotation around the joint axis in radians
  • speed – (default: value of ‘radial_speed’ property) rotation speed, in rad/s
rotate_joints(callback, *param)

Rotates a set of joints at a given speed (in rad/s).

Sees:Blender documentation on joint rotation

Note

Setting different speeds for each joints is not yet supported (but if you need it, ping morse-dev@laas.fr: it is fairly easy to add).

Parameters:
  • joint_rotations – a list of mapping {name of the armature’s joint: rotation in radian}
  • speed – (default: value of ‘radial_speed’ property) rotation speed for all joints, in rad/s
set_rotation(joint, rotation)[source]

Rotates instantaneously the given (revolute) joint by the given rotation. Joint speed limit is not taken into account.

If the joint does not exist or is not a revolute joint (hinge), throws a MorseServiceFailed exception.

The rotation is always clamped to the joint limit.

Parameters:
  • joint – name of the joint to rotate
  • rotation – absolute rotation from the joint origin along the

joint rotation axis, in radians

set_rotations(rotations)[source]

Sets in one call the rotations of the revolute joints in this armature.

Has the same effect as applying set_rotation on each of the joints independantly.

Rotations must be ordered from the root to the tip of the armature. Use the service get_joints() to retrieve the list of joints in the correct order.

If more rotations are provided than the number of joints, the remaining ones are discarded. If less rotations are provided, the maximum are applied.

Important

If a prismatic joint is encountered while applying the rotation, an exception is thrown, and no rotation is applied.

Sees:set_rotation
Parameters:rotations – a set of absolute rotations, in radians
set_translation(joint, translation)[source]

Translates instantaneously the given (prismatic) joint by the given translation. Joint speed limit is not taken into account.

Sees:Blender documentation on joint location

If the joint does not exist or is not a prismatic joint (slider), throws a MorseServiceFailed exception.

The translation is always clamped to the joint limit.

Parameters:
  • joint – name of the joint to move
  • translation – absolute translation from the joint origin in the

joint sliding axis, in meters

set_translations(translations)[source]

Sets in one call the translations of the prismatic joints in this armature.

Has the same effect as applying set_translation on each of the joints independantly.

Translations must be ordered from the root to the tip of the armature. Use the service get_joints() to retrieve the list of joints in the correct order.

If more translations are provided than the number of joints, the remaining ones are discarded. If less translations are provided, the maximum are applied.

Important

If a revolute joint is encountered while applying the translations, an exception is thrown, and no translation is applied.

Sees:set_translation
Parameters:translations – a set of absolute translations, in meters
trajectory(callback, *param)

Executes a joint trajectory to the armature.

The trajectory parameter should have the following structure:

trajectory = {
    'starttime': <timestamp in second>,
    'points': [
        {'positions': [...],
         'velocities': [...],
         'accelerations' [...],
         'time_from_start': <seconds>}
        {...},
        ...
        ]
    }

Warning

Currently, both velocities and accelerations are ignored.

The trajectory execution starts after starttime timestamp passed (if omitted, the trajectory execution starts right away).

points is the list of trajectory waypoints. It is assumed that the values in the waypoints are ordered the same way as in the set of joint of the armature (ie, from the root to the tip of the armature. Use the service get_joints() to retrieve the list of joints in the correct order.) velocities and accelerations are optional.

The component attempts to achieve each waypoint at the time obtained by adding that waypoint’s time_from_start value to starttime.

Parameters:trajectory – the trajectory to execute, as describe above.
translate(callback, *param)

Translates a joint at a given speed (in m/s).

Parameters:
  • joint – name of the armature’s joint to translate
  • translation – the absolute translation, relative to the joint

origin, in meters :param speed: (default: value of ‘linear_speed’ property) translation speed, in m/s

translate_joints(callback, *param)

Translates a set of joints at a given speed (in m/s).

Note

Setting different speeds for each joints is not yet supported (but if you need it, ping morse-dev@laas.fr: it is fairly easy to add).

Parameters:
  • joint_translations – a list of mapping {name of the armature’s joint: translation in meters}
  • speed – (default: value of ‘linear_speed’ property) rotation speed for all joints, in m/s

morse.actuators.arucomarker module

class Arucomarker(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

The ArUco marker is an AR-Marker that allows to compute the camera pose from images in the ‘real world’.

See: http://www.uco.es/investiga/grupos/ava/node/26

The purpose of this actuator is to provide a virtual instance of such a marker in MORSE. By adding an ArUco marker to a MORSE simulation you can subsequently stream/export a (virtual) camera image and eventually use an AR Marker without a physical camera setup or, i.e, test algorithms or simulate visual servoring.

from morse.builder import *

### Add a virtual ArUco marker to the scene
robot = Morsy()

aruco = Arucomarker()
aruco.add_stream('ros', topic="/aruco_pose")
aruco.properties(zoffset=0.3, xoffset=-0.09, yoffset=.0)

robot.append(aruco)

env = Environment('empty')
Noautoexample:
default_action()[source]

Base action performed by any object.

This method should be implemented by all subclasses that will be instanced (GPS, v_Omega, ATRV, etc.).

force_pose(position, orientation)[source]
get_local_orientation()[source]
get_local_position()[source]
get_world_orientation()[source]
get_world_position()[source]

morse.actuators.destination module

class Destination(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads the coordinates of a destination point, and moves the robot in a straight line towards the given point, without turning. It provides a very simplistic movement, and can be used for testing or for robots with holonomic movement. The speeds provided are internally adjusted to the Blender time measure.

default_action()[source]

Move the object towards the destination.

morse.actuators.drag module

class Drag(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator allows to simulate the drag force, or fluid resistance. It is not controlable, as it depends only of robot parameters, and environment.

The drag force is generally written as:

Fd = 0.5 * rho * vel_sq * A * Cd

where
  • rho is the density of the fluid (env dependant)
  • A is the cross sectional area (robot dependent)
  • Cd is the drag coefficient, related to the object shape and the Reynolds Number

All these values are aggregated into the property DragCoeff, to ease the configuration of the component.

default_action()[source]

Base action performed by any object.

This method should be implemented by all subclasses that will be instanced (GPS, v_Omega, ATRV, etc.).

morse.actuators.external_force module

class ExternalForce(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This class will read force and torque as input from an external middleware, and applys them to the associated robot in the global frame.

It allows to simulate impact of the environment on the robot, such as wind, flow, …

default_action()[source]

Base action performed by any object.

This method should be implemented by all subclasses that will be instanced (GPS, v_Omega, ATRV, etc.).

morse.actuators.force_torque module

class ForceTorque(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This class will read force and torque as input from an external middleware. The forces and torques are transformed from the actuator frame to the parent robot frame and then applied to the robot blender object. If the property RobotFrame is set to True it will be applied directly in the robot frame without changes.

default_action()[source]

Apply (force, torque) to the parent robot.

morse.actuators.gripper module

class Gripper(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

Actuator capable of grabbing objects marked with the Graspable Game Property. Currently it only works using services: grab and release. When instructed to grab an object, it will check if it is within range, and if so, will parent the grabbed object to itself.

Note

For objects to be detected and grabbed by the gripper, they must have the following settings in the Physics Properties panel:

  • Actor must be checked
  • Collision Bounds must be checked
  • Physics Type must be Rigid Body

This will work even for Static objects

Warning

This actuator does not simulate the physical interaction of the gripper fingers with the objects it grabs. Its purpose is to abstract the action of taking an object, for human-robot interaction experiments.

default_action()[source]

Check if an object is within reach of the hand

find_object()[source]

Store the object that is within reach of the gripper Uses a Blender Radar Sensor to detect objects with the ‘Graspable’ property in front of this component

grab()[source]

Tries to grab an object close to the gripper.

Returns:if successful (or if an object is already in hand), the name of the object, else None.
release()[source]

Free the grabbed object.

Let it fall down after resetting its rotation. Does nothing if no object is held.

Returns:True if an object has been released, else False (if no object was held).

morse.actuators.joystick module

class Joystick(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator does not require a connection with external data. It simply responds to the joystick to generate movement instructions for the robot attached.

from morse.builder import *

# adds a default robot (the MORSE mascott!)
robot = Morsy()

# creates a new instance of the joystick actuator
joystick = Joystick()
robot.append(keyboard)

env = Environment('empty')

# Run this simulation: you can move the robot with your joystick.
Noautoexample:
default_action()[source]

Interpret joystick axis push and assign them to movement for the robot.

morse.actuators.keyboard module

class Keyboard(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator does not require a connection with external data. It simply responds to the keyboard arrows to generate movement instructions for the robot attached.

When parented to a robot, the user can press the arrow keys to modify the linear and angular velocities (V, W) of the robot.

Up forward Down backwards Left turn/yaw left Right turn/yaw right I pitch forward K pitch backward L roll left M roll right U strafe left O strafe right T move up G move down

from morse.builder import *

# adds a default robot (the MORSE mascott!)
robot = Morsy()

# creates a new instance of the actuator
keyboard = Keyboard()
robot.append(keyboard)

env = Environment('empty')

# Run this simulation: you can move the robot with the arrow keys.
Noautoexample:
default_action()[source]

Interpret keyboard presses and assign them to movement for the robot.

morse.actuators.light module

class Light(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator is a simple On/Off light. Based on SPOT light.

  • Emit in +X
default_action()[source]

Switch on/off the light.

toggle(emit=None)[source]

Toggle the light.

Parameters:emit – if emit is set to True/False, switch the light On/Off; if emit is not set, toggle the light (from On to Off and conversely)
Returns:Returns always True

morse.actuators.orientation module

class Orientation(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

Motion controller changing the robot orientation.

This actuator reads the values of angles of rotation around the 3 axis and applies them to the associated robot. This rotation is applied with the speed provided in properties. For backward compatibility reasons, the default speed is infinite, so the rotation is instantaneous. Angles are expected in radians.

default_action()[source]

Change the parent robot orientation.

morse.actuators.pa_10 module

class PA10(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads a list of angles for the segments of the Mitsubishi PA-10 arm and applies them as local rotations.

Angles are expected in radians.

default_action()[source]

Apply rotation to the arm segments

set_rotation_array(seg0=0, seg1=0, seg2=0, seg3=0, seg4=0, seg5=0)[source]

MORSE service to set the rotation for each of the arm joints. It receives an array containing the angle to give to each of the robot articulations. Angles are expected in radians. The length of the array should be equal to 6 or less, where any values not specified will be considered as 0.0.

Parameters:
  • seg0 – 1st joint angle (base)
  • seg1 – 2nd joint angle
  • seg2 – 3rd joint angle
  • seg3 – 4th joint angle
  • seg4 – 5th joint angle
  • seg5 – 6th joint angle (wrist)

morse.actuators.ptu module

class PTU(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads the rotation values for pan and tilt, and applies them to the pan-tilt unit that must be set as children of this actuator. Angles are expected in radians.

Unlike most other actuators, the Pan-Tilt unit is composed not only of an Empty object, but it also includes two meshes. These are the PanBase and the TiltBase that must also be imported when using this actuator. These meshes will rotate to produce the effect of a real Pan-Tilt unit.

Note

When mounting a camera or stereo unit on top of the Pan-Tilt unit, make sure to parent the camera to the PTU object.

This component can be configured to be operated manually as well as through data from a middleware. When using manual mode, the pan and tilt segments can be rotated using the following keys:

  • Page Up tilt up
  • Page Down tilt down
  • Home pan left
  • Insert pan right
default_action()[source]

Apply rotation to the platine unit

get_pan_tilt()[source]

Returns the current angles for the pan and tilt segments.

Returns:a couple of float, representing respectively the pan and the tilt of the platine, in radian.
look_at_object(callback, *param)

Move the platine to look in the direction of the given object.

Parameters:obj_name – the (Blender) name of an object present in the scene
look_at_point(callback, *param)

Move the platine to look towards a given point. The point is expected to be given in the world reference

Parameters:
  • x – x coordinate of the target point (in meter)
  • y – y coordinate of the target point (in meter)
  • z – z coordinate of the target point (in meter)
set_pan_tilt(callback, *param)

Move the platine to a given target position, represented by an angle couple.

Parameters:
  • pan – Target pan angle, in radian
  • tilt – Target tilt angle, in radian

morse.actuators.quadrotor_dynamic_control module

class QuadrotorDynamicControl(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads speed of the four motors of the quadrotor, and computes the resulting force / moment, following the dynamic model proposed in:

  • Backstepping and Sliding-mode Technique Applied to an Indoor Micro Quadrotor
  • Control of Complex Maneuvers for a Quadrotor UAV using Geometric Methods on SE(3)

The actuator assumes that first and third properlers turns clockwise, while second and fourth turns counter-clockwise

default_action()[source]

Run attitude controller and apply resulting force and torque to the parent robot.

morse.actuators.rotorcraft_attitude module

class RotorcraftAttitude(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads roll,pitch, yaw rate (or yaw, depending the control mode) and thrust commands as e.g. used to manually control a quadrotor via RC or by higher level control loops. This controller is meant to be used by quadrotors and similar flying robots with Rigid Body physics in blender. It is a simple PD-controller which applies torques to the robot to change and control the attitude. In YawRateControl, the yaw-rate input is integrated to yield an absolute yaw setpoint for the controller, otherwise yaw is considered directly as the order. Thrust is directly applied as force in z-direction of the robot.

Note

Angle are given in aerospace North East Down convention (NED)

default_action()[source]

Run attitude controller and apply resulting force and torque to the parent robot.

morse.actuators.rotorcraft_velocity module

class RotorcraftVelocity(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This controller will receive a velocity and yaw rate command and make the robot move by changing attitude. This controller is meant for rotorcrafts like quadrotors.

default_action()[source]

Move the robot.

setvel(vx, vy, vz, vyaw, tolerance=0.1)[source]

Set a new desired velocity and return.

The robot will try to go achieve the desired velocity, but the service caller has no mean to know when the desired velocity is reached or if it failed.

Parameters:
  • vx – x coordinate of the velocity (meter/sec)
  • vy – y coordinate of the velocity (meter/sec)
  • vz – z coordinate of the velocity (meter/sec)
  • vyaw – yaw rate (radian/sec)
  • tolerance – speed difference considered to decide whether the desired velocity has been reached (meter/sec)
Returns:

True, except if the desired velocity is already reached. In this case, returns False.

morse.actuators.rotorcraft_waypoint module

class RotorcraftWaypoint(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This controller will receive a 3D destination point and heading and make the robot move to that location by changing attitude. This controller is meant for rotorcrafts like quadrotors.

default_action()[source]

Move the object towards the destination.

get_status()[source]

Return the current status (Transit or Arrived)

goto(callback, *param)

Go to a new destination.

The service returns when the destination is reached within the provided tolerance bounds.

Parameters:
  • x – x coordinate of the waypoint (meter)
  • y – y coordinate of the waypoint (meter)
  • z – z coordinate of the waypoint (meter)
  • yaw – orientation of the waypoint (radian)
  • tolerance – distance considered to decide that the waypoint has been reached (meter)
setdest(x, y, z, yaw, tolerance=0.2)[source]

Set a new waypoint and returns.

The robot will try to go to this position, but the service caller has no mean to know when the destination is reached or if it failed.

In most cases, the asynchronous service ‘goto’ should be preferred.

Parameters:
  • x – x coordinate of the waypoint (meter)
  • y – y coordinate of the waypoint (meter)
  • z – z coordinate of the waypoint (meter)
  • yaw – orientation of the waypoint (radian)
  • tolerance – distance considered to decide that the waypoint has been reached (meter)
Returns:

True (if the robot is already moving, the previous target is replaced by the new one) except if the destination is already reached. In this case, returns False.

morse.actuators.sound module

class Sound(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator is a simple On/Off sound. Based on Sound actuator.

default_action()[source]

Apply play to this actuator.

morse.actuators.stabilized_quadrotor module

class StabilizedQuadrotor(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator controls a stabilized quadrotor using a linear model. Basically, it reads a command (phi, theta, psi, h), and computes, using a second order filter the speed and the position of the robot. The quadrotor must not have Rigid Body physics.

Note

Coordinates are given with respect to the origin of Blender’s coordinate axis.

Note

The actuator does not consider friction force. Setting theta_c or phi_c to 0 leads to a constant speed on axis x or y.

default_action()[source]

Apply … to the parent robot.

set_cons(phi, theta, psi, h)[source]

Specify a consign for the robot. It has the same effect that writing the corresponding constraint in the datastream.

Parameters:
  • phi – commands the roll of the quadrotor
  • theta – command the pitch of the quadrotor
  • psi – command the yaw of the quadrotor
  • h – the expected height for the quadrotor.
stop()[source]

Stop the robot. It basically means that speed on the different axis is set to 0. Moreover, the different filters are reset.

morse.actuators.steer_force module

class SteerForce(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads the values of the steering angle, the engine power and the braking force to drive a car like vehicle. It is meant to work with robots implementing the Blender Vehicle Wrapper, such as the Hummer robot.

Note

Robots implementing the Vehicle Wrapper must be pointing towards their local Y axis. This means the robots will be oriented differently with respect to all other MORSE components.

default_action()[source]

Apply (steer, force) to the parent robot.

morse.actuators.teleport module

class Teleport(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator teleports the robot to the absolute position and orientation with respect to the origin of the Blender coordinate reference. Angles are expected in radians.

Note

Coordinates are given with respect to the origin of Blender’s coordinate axis.

default_action()[source]

Change the parent robot pose.

rotate(roll, pitch=0.0, yaw=0.0)[source]

Rotates the actuator owner by the given (roll,pitch,yaw).

This is a relative rotation.

Parameters:
  • roll – roll rotation, in radians
  • pitch – (default: 0.0) pitch rotation, in radians
  • yaw – (default: 0.0) yaw rotation, in radians
translate(x, y=0.0, z=0.0)[source]

Translate the actuator owner by the given (x,y,z) vector.

This is a relative displacement.

Parameters:
  • x – X translation, in meter
  • y – (default: 0.0) Y translation, in meter
  • z – (default: 0.0) Z translation, in meter

morse.actuators.v_omega module

class MotionVW(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads the values of linear and angular speed and applies them to the robot as direct translation. The speeds provided are internally adjusted to the Blender time measure.

default_action()[source]

Apply (v, w) to the parent robot.

set_speed(v, w)[source]

Modifies v and w according to the parameters

Parameters:
  • v – desired linear velocity (meter by second)
  • w – desired angular velocity (radian by second)
stop()[source]

Stop the robot

Internally, it sets (v, w) to (0.0, 0.0)

morse.actuators.v_omega_diff_drive module

class MotionVWDiff(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads the values of linear and angular speed and applies them to the robot as speeds for the wheels. It only works with robots of the type WheeledRobot, such as the Segway RMP 400 and the Pioneer 3-DX. The movement of the robot is more realistic, but also depends on more factors, such as the friction between the wheels and the surface.

The speeds for the left and right wheels are calculated as:

left_speed = (v - e w) / R right_speed = (v + e w) / R

where:

  • v is the linear velocity given as parameter
  • w is the angular velocity given as parameter
  • e is half of the distance between the left and

right wheels - R is the radius of the wheels

default_action()[source]

Apply (v, w) to the parent robot.

set_speed(v, w)[source]

Modifies v and w according to the parameters

Parameters:
  • v – desired linear velocity (meter by second)
  • w – desired angular velocity (radian by second)
stop()[source]

Stop the robot

Internally, it sets (v, w) to (0.0, 0.0)

morse.actuators.waypoint module

class Waypoint(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads the coordinates of a destination point, and moves the robot towards the given point, with the robot restricted to moving only forward, turning around its Z axis, and possibly going up and down. This controller is meant to be used mainly by non-holonomic robots.

While a robot is moving towards a given waypoint, a property of the Robot will be changed in indicate the status of the robot. The movement_status property will take one of these values: Stop, Transit or Arrived.

The movement speed of the robot is internally adjusted to the Blender time measure, following the formula: blender_speed = given_speed * tics, where tics is the number of times the code gets executed per second. The default value in Blender is tics = 60.

This actuator also implements a simple obstacle avoidance mechanism. The blend file contains the Motion_Controller empty, as well as two additional Empty objects: Radar.L and Radar.R. These detect nearby objects to the left or right of the robot, and will instruct the robot to turn in the opposite direction of the obstacle. If the radar objects are not present, the controller will not have any obstacle avoidance, and the robot can get blocked by any object between it and the target.

Note

For objects to be detectable by the radars, they must have the following settings in the Physics Properties panel:

  • Actor must be checked
  • Collision Bounds must be checked

This will work even for Static objects

default_action()[source]

Move the object towards the destination.

get_status()[source]

Ask the actuator to send a message indicating the current movement status of the parent robot. There are three possible states: Transit, Arrived and Stop.

goto(callback, *param)

This method can be used to give a one time instruction to the actuator. When the robot reaches the destination, it will send a reply, indicating that the new status of the robot is “Stop”.

Parameters:
  • x – x coordinate of the destination, in world frame, in meter
  • y – y coordinate of the destination, in world frame, in meter
  • z – z coordinate of the destination, in world frame, in meter
  • tolerance – tolerance, in meter, to consider the destination as reached. Optional (default: 0.5 m).
  • speed – speed to join the goal. Optional (default 1m/s)
interrupt()[source]

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.

resume()[source]

Restores the speed to the same value as before the last call to the stop service. The robot will continue to the last waypoint specified.

setdest(x, y, z, tolerance=0.5, speed=1.0)[source]

Set a new waypoint and returns.

The robot will try to go to this position, but the service caller has no mean to know when the destination is reached or if it failed.

In most cases, the asynchronous service ‘goto’ should be prefered.

Parameters:
  • x – x coordinate of the destination, in world frame, in meter
  • y – y coordinate of the destination, in world frame, in meter
  • z – z coordinate of the destination, in world frame, in meter
  • tolerance – tolerance, in meter, to consider the destination as reached. Optional (default: 0.5 m).
  • speed – speed to join the goal. Optional (default 1m/s)
Returns:

Returns always True (if the robot is already moving, the previous target is replaced by the new one) except if the destination is already reached. In this case, returns False.

stop()[source]

This method will instruct the robot to set its speed to 0.0, and reply immediately. If a goto request is ongoing, it will remain “pending”, as the current destination is not changed.

morse.actuators.xy_omega module

class MotionXYW(obj, parent=None)[source]

Bases: morse.core.actuator.Actuator

This actuator reads the values of forwards movement x, sidewards movement y and angular speed w and applies them to the robot as direct translation. This controller is supposed to be used with robots that allow for sidewards movements.

default_action()[source]

Apply (x, y, w) to the parent robot.

Module contents