The ABR Control library is a python package for the control and path planning of robotic arms in real or simulated environments.

Overview

https://imgur.com/4qIqbRn.jpg

ABR Control

The ABR Control library is a python package for the control and path planning of robotic arms in real or simulated environments. ABR Control provides API's for the Mujoco, CoppeliaSim (formerly known as VREP), and Pygame simulation environments, and arm configuration files for one, two, and three-joint models, as well as the UR5 and Kinova Jaco 2 arms. Users can also easily extend the package to run with custom arm configurations. ABR Control auto-generates efficient C code for generating the control signals, or uses Mujoco's internal functions to carry out the calculations.

ABR also provides an interface and config available for controlling a real Jaco 2 at the ABR_Jaco2 repository.

Installation

The ABR Control library depends on NumPy, SymPy, SciPy, CloudPickle, Cython, SetupTools, Nengo, and Matplotlib. We recommend using Anaconda. Note that installing in a clean environment will require compiling of the dependent libraries, and will take a few minutes.

To install ABR Control, clone this repository and run:

sudo apt-get install g++
sudo apt-get install python-dev
sudo apt-get install libfreetype6-dev
conda activate your_environment
python setup.py install
python setup.py develop

ABR Control is tested to work on Python 3.6+, Python 2 is not supported.

Optional Installation

Mujoco

If you would like to use the Mujoco API you will need to install a forked version of mujoco-py with hooks for exitting out of simulations with the ESC key. To use the mujoco API, make sure you are in your anaconda environment and run:

git clone https://github.com/studywolf/mujoco-py.git
cd mujoco-py
pip install -e .
pip install glfw>=1.8.3
pip install requests

Pygame

If you would like to use the Pygame API, from your anaconda environment run:

pip install pygame

Vrep

We support Vrep <=4.0. You will need to download Vrep and follow the installation instructions.

PyDMPs

Some of the path planners work through the use of dynamic movement primitives (DMPs). DMPs allow for a stable, generalizable, and easily extensible way of representing complex trajectories. Path planners making use of DMP are appended with 'dmp' in their filename and will require the installation of the pydmps repository. To install, from your Anaconda environment run:

pip install pydmps

Usage

The ABR Control repo is comprised of three parts: 1) arms, 2) controllers, and 3) interfaces.

1a) Arms: Using CoppeliaSim, Pygame, or a real arm

All of the required information about an arm model is kept in that arm's config file. To use the ABR Control library with a new arm, the user must provide the transformation matrices (written using SymPy expressions) from the robot's origin reference frame to each link's centre-of-mass (COM) and joints. These are specified sequentially, e.g. origin -> link0 COM, link0 COM -> joint0, joint0 -> link1 COM, etc. The arm config file and any simulation code is kept in a folder named the same as the arm in the abr_control/arms/ directory.

The ABR Control configuration base class uses the SymPy transform matrices to provide functions that will calculate the transforms, Jacobian, Jacobian derivative, inertia matrices, gravity forces, and centripetal and Coriolis effects for each joint and COM. These can be accessed:

from abr_control.arms import jaco2

robot_config = jaco2.Config()
# calculate the following given the arm state at joint_angles
robot_config.Tx('joint3', q=joint_angles)  # the (x, y, z) position of joint3
robot_config.M(q=joint_angles)  # calculate the inertia matrix in joint space
robot_config.J('EE', q=joint_angles)  # the Jacobian of the end-effector

By default, the use_cython parameter is set to True to allow for real-time control by generating optimized Cython code for each of the robot configuration functions. This can take a little bit of time to generate these functions, but they are saved in ~.cache/abr_control/arm_name/saved_functions where they will be loaded from for future runs. Note that a hash is saved for the config, so if any changes are made the functions will be regenerated during the next use. The cython optimization can be turned off on instantiation:

from abr_control.arms import ur5

robot_config = ur5.Config(use_cython=False)

Below are results from running the operational space controller with different controllers with use_cython=True and False.

docs/examples/timing.png

1b) Arms: Using Mujoco

When using Mujoco the process is a bit different. Mujoco handles the calculation of all the kinematics and dynamics functions, and only requires an xml config be made describing the kinematic chain. The Mujoco API page describes this in detail.

Detailed models can be created by importing 3D modeling stl files and using the mesh object type in the tag. An example of this is the abr_control/arms/jaco2/jaco2.xml. For users building their own models, you may specify the location of the xml with the folder parameter. For more details, please refer to the Mujoco documentation linked above and use the xml files in this repository as examples.

2) Controllers

Controllers make use of the robot configuration files to generate control signals that accomplish a given task (for most controllers this is reaching a target). The ABR Control library provides implementations of several primary controllers, including operational space, generalized coordinates (joint) space, sliding, and floating control.

When using an operational space controller, it is possible to also pass in secondary controllers to operate in the null space of the operational space controller. These secondary controllers can be set up to achieve secondary goals such as avoiding joint limits and obstacles, damping movement, or maintaining a configuration near a specified resting state.

In the path_planners folder there are several path planners that can be used in conjunction with the controllers. There are filters, linear and second order, which can be used to trace a path from the current position to the target without suddenly warping and causing large spikes in generated torque. The inverse kinematics planner takes in a target for the end-effector and returns a joint angle trajectory to follow. An arc path planner is also provided that creates an arcing path which can be useful when the arm has to reach over itself. This can help prevent self-collisions and odd arm configurations.

Each path planner also has the ability to generate a trajectory for end-effector orientation with the path_plannner.generate_orientation_path() function. This uses spherical linear interpolation (SLERP) to generate a set of orientations from a start to a target quaternion. The time profile will match that of the path planner instantiated (ie: a linear path planner will have a linear step in orientation over time, with a constant change in orientation, whereas a second order path planner will have a bell shaped profile with the largest steps occurring during the middle of the movement, with an acceleration and deceleration at the start and end, respectively.) In addition to filters, there is an example path planner using the dynamic movement primitives trajectory generation system.

Finally, there is an implementation of nonlinear adaptive control in the signals folder, as well as examples in Mujoco, PyGame, and CoppeliaSim showing how this class can be used to overcome unexpected forces acting on the arm.

3) Interfaces

For communications to and from the system under control, an interface API is used. The functions available in each class vary depending on the specific system, but must provide connect, disconnect, send_forces and get_feedback methods.

Putting everything together

A control loop using these three files looks like:

from abr_control.arms import jaco2
from abr_control.controllers import OSC
from abr_control.interfaces import CoppeliaSim

robot_config = jaco2.Config()
interface = CoppeliaSim(robot_config)
interface.connect()

ctrlr = OSC(robot_config, kp=20,
            # control (x, y, z) out of [x, y, z, alpha, beta, gamma]
            ctrlr_dof=[True, True, True, False, False, False])

target_xyz = [.2, .2, .5]  # in metres
target_orientation = [0, 0, 0]  # Euler angles, relevant when controlled
for ii in range(1000):
    feedback = interface.get_feedback()  # returns a dictionary with q, dq
    u = ctrlr.generate(
        q=feedback['q'],
        dq=feedback['dq'],
        target=np.hstack([target_xyz, target_orientation]))
    interface.send_forces(u)  # send forces and step CoppeliaSim sim forward

interface.disconnect()

NOTE that when using the Mujoco interface it is necessary to instantiate and connect the interface before instantiating the controller. Some parameters only get parsed from the xml once the arm config is linked to the mujoco interface, which happens upon connection.

Examples

The ABR Control repo comes with several examples that demonstrate the use of the different interfaces and controllers.

By default all of the PyGame examples run with the three-link MapleSim arm. You can also run the examples using the two-link Python arm by changing the import statement at the top of the example scripts.

To run the CoppeliaSim examples, have the most recent CoppeliaSim version open. By default, the CoppeliaSim examples all run with the UR5 or Jaco2 arm model. To change this, change which arm folder is imported at the top of the example script. The first time you run an example you will be promted to download the arm model. Simply select yes to download the file and the simulation will start once the download completes.

To run the Mujoco examples, you will be promted to download any mesh or texture files, if they are used in the xml config, similarly to the CoppeliaSim arm model. Once the download completes the simulation will start. If you are using the forked Mujoco-Py repository (See Optional Installation section) you can exit the simulation with the ESC key and pause with the spacebar.

Owner
Applied Brain Research
Applied Brain Research
Terkin is a flexible data logger application for MicroPython and CPython environments.

Terkin Data logging for humans, written in MicroPython. Documentation: https://terkin.org/ Source Code: https://github.com/hiveeyes/terkin-datalogger

hiveeyes 45 Dec 15, 2022
Blender Camera Switcher

Blender Camera Switcher A simple camera switcher addon for blender. Useful when use reference image for camera. This addon will automatically fix the

Corgice 1 Jan 31, 2022
Home assiatant Custom component: Camera Archiver

Camera archiver Archive your ftp camera meadia files on other ftp with files renaming and event creation. Event can be used for send information to el

1 Jan 06, 2022
gdsfactory is an EDA (electronics design automation) tool to Layout Integrated Circuits.

gdsfactory 3.5.5 gdsfactory is an EDA (electronics design automation) tool to Layout Integrated Circuits. It is build on top of phidl gdspy and klayou

147 Jan 04, 2023
It is a program that displays the current temperature of the GPU and CPU in real time and stores the temperature history.

HWLogger It is a program that displays the current temperature of the GPU and CPU in real time and stores the temperature history. Sample Usage Run HW

Xeros 0 Apr 05, 2022
This is an incredible led matrix simulation using the ultimate mosaik co-simulation framework.

This project uses the mosaik co-simulation framework, developed by the brilliant developers at the high-ranked Offis institue for computer science, Oldenburg, Germany, to simulate multidimensional LE

Felix 1 Jan 28, 2022
Used python functional programming to make this Ai assistant

Python-based-AI-Assistant I have used python functional programming to make this Ai assistant. Inspiration of project : we have seen in our daily life

Durgesh Kumar 2 Dec 26, 2021
How to configure IOMMU device for nested Proxmox hypervisor (PVE) VM - PCIe Passthrough

Configuring PCIe Passthrough for Nested Virtualization on Proxmox Summary: If you are running bare-metal L0 (level 0) Proxmox (PVE) hypervisor with ne

Travis Johnson 6 Aug 30, 2022
Python module for the qwiic serial control motor driver

Qwiic_SCMD_Py Python module for the qwiic motor driver This python package is a port of the existing SparkFun Serial Controlled Motor Driver Arduino L

SparkFun Electronics 6 Dec 06, 2022
[unmaintained] WiFi tools for linux

Note: This project is unmaintained. While I would love to keep up the development on this project, it is difficult for me for several reasons: I don't

Rocky Meza 288 Dec 13, 2022
Ansible tools for operating and managing fleets of Blinksticks in harmony using the Blinkstick Python library.

Ansible tools for operating and managing fleets of Blinksticks in harmony using the Blinkstick Python library.

Greg Robinson 3 Aug 10, 2022
Python implementation of ZMP Preview Control approach for biped robot control.

ZMP Preview Control This is the Python implementation of ZMP Preview Control app

Chaobin 24 Dec 19, 2022
A ch341dll Wrap is for using in Python 32bits windows to access I2C SPI and MDIO (by GPIO), and Demo with display PC sreen on OLED by i2c or SPI .

ch341dll_wrap_typcal_app A ch341dll Wrap is for using in Python 32bits windows to access I2C SPI and MDIO (by GPIO). In addition, I provided 3 Demo. I

13 Jan 02, 2023
Python code written to utilize the Korlan usb2can hardware to send and receive data over the can-bus on a 2008 Nissan 350z

nissan_ecu_hacking Python code written to utilize the Korlan usb2can hardware to send and receive data over the can-bus on a 2008 Nissan 350z My goal

Liam Goss 11 Sep 24, 2022
ArucoFollow - A script for Robot Operating System and it is a part of a project Robot

ArucoFollow ArucoFollow is a script for Robot Operating System and it is a part

5 Jan 25, 2022
OctoPrint is the snappy web interface for your 3D printer!

OctoPrint OctoPrint provides a snappy web interface for controlling consumer 3D printers. It is Free Software and released under the GNU Affero Genera

OctoPrint 7.1k Jan 03, 2023
Iec62056-21-mqtt - Publish DSMR P1 telegrams acquired over IEC62056-21 to MQTT

IEC 62056-21 Publish DSMR P1 telegrams acquired over IEC62056-21 to MQTT. -21 is

Marijn Suijten 1 Jun 05, 2022
A script that publishes power usage data of iDrac enabled servers to an MQTT broker for integration into automation and power monitoring systems

iDracPowerMonitorMQTT This script publishes iDrac power draw data for iDrac 6 enabled servers to an MQTT broker. This can be used to integrate the pow

Lucas Zanchetta 10 Oct 06, 2022
Count the number of people around you 👨‍👨‍👦 by monitoring wifi signals 📡 .

howmanypeoplearearound Count the number of people around you 👨‍👨‍👦 by monitoring wifi signals 📡 . howmanypeoplearearound calculates the number of

Zack 6.7k Jan 07, 2023
New armachat based on Raspberry Pi PICO an Circuitpython code

Armachat-circuitpython New Armachat based on Raspberry Pi PICO an Circuitpython code Software working features: send message with header and store to

Peter Misenko 44 Dec 24, 2022