Actuators

Actuator

class crappy.actuator.actuator.Actuator[source]

The base class for all actuator classes, allowing to keep track of them and defining methods shared by all of them.

get_position() float | None[source]

This method should return the current position of the actuator. It is also fine for this method to return None.

get_speed() float | None[source]

This method should return the current speed of the actuator. It is also fine for this method to return None.

set_position(position: float, speed: float | None = None) None[source]

This method should drive the actuator so that it reaches the desired position. A speed value can optionally be provided for specifying the speed at which the actuator should move for getting to the desired position.

set_speed(speed: float) None[source]

This method should drive the actuator so that it reaches the desired speed.

class crappy.actuator.actuator.MetaActuator(name: str, bases: tuple, dct: dict)[source]

Metaclass ensuring that two Actuators don’t have the same name, and that all Actuators define the required methods. Also keeps track of all the Actuator classes, including the custom user-defined ones.

Biaxe

class crappy.actuator.biaxe.Biaxe(port: str = '/dev/ttyUSB0', baudrate: int = 38400, timeout: float = 1)[source]

This class creates an axis and opens the corresponding serial port.

__init__(port: str = '/dev/ttyUSB0', baudrate: int = 38400, timeout: float = 1) None[source]

Sets the instance attributes.

Parameters:
  • port (str, optional) – Path to the corresponding serial port, e.g ‘/dev/ttyS4’.

  • baudrate (int, optional) – Set the corresponding baud rate.

  • timeout (float, optional) – Serial timeout.

clear_errors() None[source]

Reset errors.

close() None[source]

Close the designated port.

set_speed(speed: float) None[source]

Re-define the speed of the motor.

1 = 0.002 mm/s

Biotens

class crappy.actuator.biotens.Biotens(port: str = '/dev/ttyUSB0', baudrate: int = 19200)[source]

Open the connection, and initialise the Biotens.

Note

You should only use this class to communicate with the Biotens.

__init__(port: str = '/dev/ttyUSB0', baudrate: int = 19200) None[source]

Sets the instance attributes.

Parameters:
  • port (str, optional) – Path to connect to the serial port.

  • baudrate (int, optional) – Set the corresponding baud rate.

clear_errors() None[source]

Clears error in motor registers.

get_position() float[source]

Reads current position.

Returns:

Current position of the motor.

reset_position() None[source]

Actuators goes out completely, in order to set the initial position.

set_position(position: float, speed: float | None = None) None[source]

Pilot in position mode, needs speed and final position to run (in mm/min and mm).

set_speed(speed: float) None[source]

Pilot in speed mode, requires speed in mm/min.

stop() None[source]

Stop the motor.

crappy.actuator.biotens.convert_to_byte(number: float, length: str) bytes[source]

This functions converts decimal into bytes.

Mandatory in order to send or read anything into/from MAC Motors registers.

crappy.actuator.biotens.convert_to_dec(sequence: bytes) float[source]

This functions converts bytes into decimals.

Mandatory in order to send or read anything into/from MAC Motors registers.

CM Drive

class crappy.actuator.cmDrive.CM_drive(port: str = '/dev/ttyUSB0', baudrate: int = 9600)[source]

Open a new default serial port for communication with a CMdrive actuator.

__init__(port: str = '/dev/ttyUSB0', baudrate: int = 9600) None[source]

Sets the instance attributes.

Parameters:
  • port (str, optional) – Path to connect to the serial port.

  • baudrate (int, optional) – Set the corresponding baud rate.

clear_errors() None[source]

Reset errors.

close() None[source]

Close the designated port.

get_position() float[source]

Search for the physical position of the motor.

Returns:

Physical position of the motor.

move_home() None[source]

Reset the position to zero.

reset() int[source]

Reset the serial communication, before reopening it to set displacement to zero.

set_position(position: float, _: float | None = None, motion_type: str = 'relative') None[source]

Pilot in position mode, needs speed and final position to run (in mm/min and mm).

set_speed(speed: float) None[source]

Pilot in speed mode, requires speed in mm/min.

stop() None[source]

Stop the motor motion.

Fakemotor

class crappy.actuator.fakemotor.Fake_motor(inertia: float = 0.5, torque: float = 0.0, kv: float = 1000, rv: float = 0.4, fv: float = 2e-05, sim_speed: float = 1, initial_speed: float = 0, initial_pos: float = 0, **kwargs)[source]

To run test programs without a physical actuator.

Note

A virtual motor driven by a voltage, you can set its properties with the args. It has the same methods as a real motor: open(), set_speed(), get_speed(), get_position().

__init__(inertia: float = 0.5, torque: float = 0.0, kv: float = 1000, rv: float = 0.4, fv: float = 2e-05, sim_speed: float = 1, initial_speed: float = 0, initial_pos: float = 0, **kwargs) None[source]

Sets the instance attributes.

Parameters:
  • inertia (float, optional) – Inertia of the motor (kg.m²).

  • torque (float, optional) – A torque applied on the axis (N.m).

  • kv (float, optional) – The electrical constant of the motor (t/min/V).

  • rv (float, optional) – The solid friction.

  • fv (float, optional) – The fluid friction.

  • sim_speed (float, optional) – Speed factor of the simulation.

  • initial_speed (float, optional) – (rpm)

  • initial_pos (float, optional) – (turns)

get_position() float[source]

Returns the motor position.

get_speed() float[source]

Return the motor speed (rpm).

set_speed(u: float) None[source]

Sets the motor cmd in volts.

update() None[source]

Updates the motor rpm.

Note

Supposes u is constant for the interval dt.

Motorkit pump

class crappy.actuator.motorkit_pump.DC_motor_hat(motor_nrs: list, device_address: int = 96, i2c_port: int = 1, bus: ft232h_server | None = None)[source]

Class for driving Adafruit’s DC motor HAT.

This class serves as a basis for building Actuators in Crappy, but is not one itself. It is used by the Motorkit_pump Actuator.

Note

This device can also drive stepper motors, but this feature isn’t included here.

It is intended for Raspberry Pis but can also be used from any other device interfacing over I2C assuming a proper wiring.

__init__(motor_nrs: list, device_address: int = 96, i2c_port: int = 1, bus: ft232h_server | None = None) None[source]

Resets the HAT and initializes it.

Parameters:
  • motor_nrs (list) – The list of the motors to drive. Its elements should be integers between 1 and 4, corresponding to the number of the motors.

  • device_address (int, optional) – The I2C address of the HAT. The default address is 0x60, but it is possible to change this setting by cutting traces on the board.

  • i2c_port (int, optional) – The I2C port over which the ADS1115 should communicate. On most Raspberry Pi models the default I2C port is 1.

  • bus (ft232h_server, optional) – If given, the I2C commands are sent by the corresponding ft232h_server instance, in the situation when the hat is controlled from a PC through an FT232H rather than by a board.

close() None[source]

Closes the I2C bus.

set_motor(nr: int, cmd: float) None[source]

Sets the PWMs associated with a given motor.

Parameters:
  • nr (int) – The number of the motor to drive.

  • cmd (float) – The command, that should be between -1 and 1.

class crappy.actuator.motorkit_pump.Motorkit_pump(backend: str, device_address: int = 96, i2c_port: int = 1, ft232h_ser_num: str | None = None)[source]

Class for controlling two DC air pumps and a valve.

It uses Adafruit’s DC motor HAT. The motor 1 controls the inflation pump, the motor 2 controls a valve, and the motor 3 controls a deflation pump.

__init__(backend: str, device_address: int = 96, i2c_port: int = 1, ft232h_ser_num: str | None = None) None[source]

Checks the validity of the arguments.

Parameters:
  • backend (str) –

    Should be one of :

    'Pi4', 'blinka', 'ft232h'
    

    The ‘Pi4’ backend is optimized but only works on boards supporting the smbus2 module, like the Raspberry Pis. The ‘blinka’ backend may be less performant and requires installing Adafruit’s modules, but these modules are compatible with and maintained on a wide variety of boards. The ‘ft232h’ backend allows controlling the hat from a PC using Adafruit’s FT232H USB to I2C adapter. See Crappy for embedded hardware for details.

  • device_address (int, optional) – The I2C address of the HAT. The default address is 0x60, but it is possible to change this setting by cutting traces on the board.

  • i2c_port (int, optional) – The I2C port over which the HAT should communicate. On most Raspberry Pi models the default I2C port is 1.

  • ft232h_ser_num (str, optional) – If backend is ‘ft232h’, the serial number of the ft232h to use for communication.

close() None[source]

Stops the pumps and closes the HAT object.

open() None[source]

Initializes the generic HAT object.

set_speed(volt: float) None[source]

Inflates or deflates the setup according to the command.

Parameters:

volt (float) – The voltage to supply to the pumps. If positive, will inflate, if negative will deflate, and if 0 won’t do anything. The voltage is clamped between -12 and 12 Volts, as it is the limit of the HAT.

stop() None[source]

Simply sets the voltage to 0.

Oriental

class crappy.actuator.oriental.Oriental(baudrate: int = 115200, port: str = '/dev/ttyUSB0', gain: float = 14.285714285714285)[source]

To drive an axis with an oriental motor through a serial link.

The current setup moves at .07mm/min with “VR 1”.

__init__(baudrate: int = 115200, port: str = '/dev/ttyUSB0', gain: float = 14.285714285714285) None[source]

Sets the instance attributes.

Parameters:
  • baudrate (int, optional) – Set the corresponding baud rate.

  • port (str, optional) – Path to connect to the serial port.

  • gain (float, optional) – The gain for speed commands.

get_position() float[source]

Reads current position.

Returns:

Current position of the motor.

set_position(position: float, speed: float | None = None) None[source]

Pilot in position mode, needs speed and final position to run (in mm/min and mm).

set_speed(cmd: float) None[source]

Pilot in speed mode, requires speed in mm/min.

stop() None[source]

Stop the motor.

Pololu Tic

class crappy.actuator.pololu_tic.Find_serial_number(serial_number: str)[source]

A class used for finding USB devices matching a given serial number, using the usb.core.find() method.

class crappy.actuator.pololu_tic.Pololu_tic(steps_per_mm: float, current_limit: float, step_mode: int | str = 8, max_accel: float = 20, t_shutoff: float = 0, config_file: str | None = None, serial_number: str | None = None, model: str | None = None, reset_command_timeout: bool = True, backend: str = 'USB', unrestricted_current_limit: bool = False, pin_function: Dict[str, str] | None = None, pin_polarity: Dict[str, str] | None = None)[source]

Class for controlling Pololu’s Tic stepper motor divers.

The Pololu_tic Actuator block is meant for controlling a Pololu Tic stepper motor driver. It can be driven in both speed and position. Several Tic models are supported. The length unit is the millimeter (mm), and time unit is the second (s).

Important

Only for Linux users: In order to drive the Tic, the appropriate udev rule should be set. This is done automatically when installing ticcmd, or can be done using the udev_rule_setter utility in crappy’s util folder. It is also possible to add it manually by running:

$ echo "SUBSYSTEM==\"usb\", ATTR{idVendor}==\"1ffb\", MODE=\"0666\"" | sudo tee pololu.rules > /dev/null 2>&1

in a shell opened in /etc/udev/rules.d.

__init__(steps_per_mm: float, current_limit: float, step_mode: int | str = 8, max_accel: float = 20, t_shutoff: float = 0, config_file: str | None = None, serial_number: str | None = None, model: str | None = None, reset_command_timeout: bool = True, backend: str = 'USB', unrestricted_current_limit: bool = False, pin_function: Dict[str, str] | None = None, pin_polarity: Dict[str, str] | None = None) None[source]

Checks args validity, finds the right device, reads the current limit tables.

Parameters:
  • steps_per_mm (float) – The number of full steps needed for the motor to travel 1mm. This varies according to the motor model, and can be deduced from the datasheet or directly measured. This value is usually between 50 and 500.

  • current_limit (float) – The maximum current the motor is able to withstand, in mA. It is usually around 1A for small stepper motors, and can go up to a few Amps. The maximum allowed current_limit value depends on the Tic model. The Tic 36v4 default maximum current limit can be increased using the unrestricted_current_limit parameter.

  • step_mode (int, optional) – Sets the number of microsteps used for driving the motor. This number is always a power of 2. The minimum number of microsteps is 1 (full steps), and the maximum depends on the Tic model. All models however support modes 1 to 8. The block manages speed and length conversions so that changing the step mode doesn’t affect the motor behaviour.

  • max_accel (float, optional) – The maximum allowed acceleration for the motor, in mm/s². When asked to reach a given speed or position, the motor accelerates at this rate. It also corresponds to the maximum allowed deceleration. Usually doesn’t need to be changed.

  • t_shutoff (float, optional) – The Pololu_tic block features an auto-shutoff thread that deenergizes the motor after a period of t_shutoff seconds of inactivity. The timer counts in steps of 0.1s, which is thus the maximum precision for this setting. When set to 0, this feature is disabled and the motor remains energized until the close() method is called.

  • config_file (str, optional) – The path of the config file to be loaded to the Tic. It only works if backend is ‘ticcmd’. The config file contains some specific settings that can only be accessed this way using the ‘ticcmd’ backend. Not necessary for most applications.

  • serial_number (str, optional) – The serial number of the Tic to be controlled. It must be given as a str, and it is an 8-digits number. Allows to control the right device if several Tic of the same model are connected. Otherwise, an error is raised.

  • model (str, optional) –

    The model of the Tic to be controlled. Available models are:

    'T825', 'T824', 'T500', 'N825', 'T249', '36v4'
    

    Allows to control the right device if several Tic of different models are connected. Otherwise, an error is raised.

  • reset_command_timeout (bool, optional) – Enables or disables the reset_command_timeout thread. It can only be disabled if backend is ‘USB’. This thread pings the Tic every 0.5s, so that it doesn’t block due to a Command Timeout error. This feature is a safety to prevent the motor from running indefinitely if the USB connection is down, so it is better not to disable it. When disabled the Tic never raises Command Timeout errors, and a bit of memory if freed because of the thread not running.

  • backend (str, optional) –

    The backend for communicating with the Tic. Available backends are:

    'USB', 'ticcmd'
    

    They both communicate over USB, but ‘ticcmd’ requires Pololu’s firmware to be installed. Some features are specific to each backend.

  • unrestricted_current_limit (bool, optional) – Enables or disables the unrestricted current limit feature. Only works if backend is ‘USB’, and for the 36v4 Tic model. When disabled, the maximum current allowed is 3939mA. If enabled, it goes up to 9095mA. The Tic should however be cooled in order to withstand currents higher than 3939mA.

  • pin_function (dict, optional) –

    Allows setting the Tic GPIO functions. It is a dict whose keys are the pin names, and values are the functions. Only works if backend is ‘USB’. Only the pins indicated in pin_function are set, the others are left in their previous state. The available pins are:

    'SCL', 'SDA', 'TX', 'RX', 'RC'
    

    and can be set to:

    'Default', 'Kill switch', 'Limit switch forward', 'Limit switch reverse'
    

    The GPIO functions remain set as long as they are not changed by the user, so for a given setup it is only necessary to set them once.

  • pin_polarity (dict, optional) –

    Allows setting the polarity of the GPIOs used as switches. It is a dict, whose keys are the pin names, and values are the pin polarities. Only works if backend is ‘USB’. Only the pins indicated in pin_function are set, the others are left in their previous state. The available pins are:

    'SCL', 'SDA', 'TX', 'RX', 'RC'
    

    and can be set to:

    'Active high', 'Active low'
    

    The GPIO polarities remain set as long as they are not changed by the user, so for a given setup it is only necessary to set them once.

Warning

  • current_limit: If the current_limit setting is higher than the motor max current, there’s a risk of overheating and damaging the motor !

Note

  • steps_per_mm: If you have to measure this value, it can be done easily following this procedure. Set steps_per_mm to spm (100 should be fine), and step_mode to sm (8 should be fine). Run a crappy program for moving the motor from position 0 to position p (a few tenth of millimeters should be fine). The motor will reach an actual position ap that can be measured. The actual steps_per_mm value aspm for this motor can be calculated as follows:

    aspm = spm * p / ap
    
  • step_mode: Increasing the number of microsteps allows to reduce the noise, the vibrations, and improve the precision. However, the more microsteps, the lower the maximum achievable speed for the motor. Chances that the motor misses microsteps are also higher when the number of microsteps is high.

  • t_shutoff: This functionality was originally added for long assays in temperature controlled environments, so that the motor doesn’t unnecessarily heat the setup when inactive. In other assays, it may still be useful for reducing the noise, the electromagnetic interference, or the energy consumption.

  • serial_number: Serial numbers can be accessed using the lsusb command in Linux shell, or running ticcmd --list if ticcmd is installed. This number is also printed during __init__() if only one device is connected and serial_number is None.

  • model: The model is written on the Tic board, and can be accessed by running ticcmd --list in a shell if ticcmd is installed. It is also printed during __init__() if only one device is connected and model is None.

  • Pins settings: The pin functions and polarity can also be set independently of crappy before starting the assay, in the ticgui.

close() None[source]

Stops the motor, joins the threads and deenergizes the motor.

get_position() float[source]

Reads the current motor position.

Returns:

float – The position in mm

get_speed() float[source]

Reads the current motor speed.

Returns:

float – The speed in mm/s

open() None[source]

Sets the communication, the motor parameters and starts the threads.

set_position(position: float, speed: float | None = None) None[source]

Sends a position command to the motor.

Parameters:
  • position (float) – The position to reach in mm

  • speed (float, optional) – The speed at which the motor should move to the given position, in mm/s

Note

  • speed: The only way to reach a position at a given speed is to change the maximum speed. The Tic will try to accelerate to the maximum speed but may remain slower if it doesn’t have time to do so before reaching the given position.

set_speed(speed: float) None[source]

Sends a speed command to the motor.

Parameters:

speed (float) – The speed the motor should reach

stop() None[source]

Sets the speed to 0.

Servostar

class crappy.actuator.servostar.Servostar(device: str, baudrate: int = 38400, mode: str = 'serial')[source]

To drive and configure a servostar variator through a serial connection.

__init__(device: str, baudrate: int = 38400, mode: str = 'serial') None[source]

Sets the instance attributes.

Parameters:
  • device (str) – Path to connect to the serial port.

  • baudrate (int, optional) – Set the corresponding baud rate.

  • mode (str, optional) – Can be ‘analog’ or ‘serial’.

clear_errors() None[source]

Clears error in motor registers.

get_position() float | None[source]

Reads current position.

Returns:

Current position of the motor.

set_mode_analog() None[source]

Sets the analog input as setpoint.

set_mode_serial() None[source]

Sets the serial input as setpoint.

set_position(pos: float, speed: float = 20000, acc: float = 200, dec: float = 200) None[source]

Go to the position specified at the given speed and acceleration.

stop() None[source]

Stops the motor.

TRA6PPD

class crappy.actuator.tra6ppd.Tra6ppd(baudrate: int = 57600, port: str = '/dev/ttyUSB0')[source]

Drives the TRA6PPD linear actuator in position.

Warning

This actuator cannot handle a high serial messages rate. It is recommended to set the frequency of the corresponding Machine block to a few dozen Hz at most.

Note

This actuator ignores new position commands while it is moving.

__init__(baudrate: int = 57600, port: str = '/dev/ttyUSB0') None[source]

Sets the instance attributes.

Parameters:
  • baudrate – The serial baud rate.

  • port – Path to the serial port to connect to.

close() None[source]

Just closes the serial port.

get_position() float[source]

Reads the current position.

Returns:

Current position of the motor.

open() None[source]

Resets the device and performs homing.

set_position(position: float, speed: float = 0.2) None[source]

Sends the actuator a command to reach a given position.

The command is ignored if the actuator is already moving.

Parameters:
  • position – The position to reach. Should be between 0 and 6 mm.

  • speed – The speed at which the actuator should move. Should be between 0 and 0.2 mm/s.

stop() None[source]

Stops the motor and sets the device to “disable” state.