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
Open-Source board for converting RaspberryPI to Brain-computer interface

The easiest way to the neuroscience world with the shield for RaspberryPi - PIEEG (website). Open-source. Crowdsupply This project is the result of se

Ildaron 436 Jan 01, 2023
Estimation of whether or not the persons given information will have diabetes.

Diabetes Business Problem : It is desired to develop a machine learning model that can predict whether people have diabetes when their characteristics

Barış TOKATLIOĞLU 0 Jan 20, 2022
ok-system-helper是一个简单的系统硬件的实时信息收集工具,使用python3.x开发

ok-system-helper ok-system-helper是一个简单的系统硬件的实时信息收集工具,使用python3.x开发,支持哪些硬件:CPU、内存、SWAP、磁盘、网卡流量。用户可在自己的项目中直接引入、开箱即用,或者结合flask等web框架轻松做成http接口供前端调用,亦可通过注

xlvchao 1 Feb 08, 2022
A LiteX project which builds a SoC with DRAM / HDIM output via the GPDI SYZYGY addon.

ButterStick GPDI LiteX demo A LiteX project which builds a SoC with DRAM / HDIM output via the GPDI SYZYGY addon. Getting started Connect GPDI board t

4 Nov 21, 2021
Python library to manipulate Ingenico mobile payment device like iCT220 or iWL220 equipped with Telium Manager. RS232/USB.

Python library to manipulate Ingenico mobile payment device like iCT220 or iWL220 equipped with Telium Manager. RS232/USB.

TAHRI Ahmed R. 72 Dec 24, 2022
Monitor an EnvisaLink alarm module running Honeywell firmware, and set a Nest device to Home/Away depending on whether the alarm is Disarmed/Away.

Nestalarm Monitor an EnvisaLink alarm module running Honeywell firmware, and set a Nest device to Home/Away depending on whether the alarm is Disarmed

1 Dec 30, 2021
Get input from OLED Joystick, Runs command, Displays output on OLED Screen (Great for P4wnP1)

p4wnsolo-joyterm Gets text input from OLED Joystick Runs the command you typed Displays output on OLED Screen (Great for P4wnP1 - even better on Raspb

PawnSolo 7 Dec 19, 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
Small Robot, with LIDAR and DepthCamera. Using ROS for Maping and Navigation

🤖 RoboCop 🤖 Small Robot, with LIDAR and DepthCamera. Using ROS for Maping and Navigation Made by Clemente Donoso, 📍 Chile 🇨🇱 RoboCop Lateral Fron

Clemente Donoso Krauss 2 Jan 04, 2022
Raspberry Pi Pico development platform for PlatformIO

Raspberry Pi Pico development platform for PlatformIO A few words in the beginning Before experimental please Reinstall the platform Version: 1.0.0 Th

Georgi Angelov 160 Dec 23, 2022
Watson-Assistant with integration capabilities

Watson-Assistant-Integration Watson-Assistant with integration capabilities "main.py" should be deployed as Cloud Function (Action) on IBM Cloud. For

Sergey Usachev 1 Dec 20, 2021
My 500 LED xmas tree

xmastree2020 This repository contains the code used for Matt's Christmas tree, as featured in "I wired my tree with 500 LED lights and calculated thei

Stand-up Maths 581 Jan 07, 2023
A install script for installing qtile and my configs on Raspberry Pi OS

QPI OS - Qtile + Raspberry PI OS Qtile + Raspberry Pi OS :) Installation Run this command in the terminal

RPICoder 3 Dec 19, 2021
Sticklog2heatmap - Draw a heatmap of RC sticks from OpenTX logs or USB HID device

sticklog2heatmap Draw a heatmap of RC sticks from OpenTX logs or USB HID device

2 Feb 02, 2022
Интеграция Home Assistant с ЛК "Интер РАО"

ЕЛК ЖКХ «Интер РАО» для Home Assistant Предоставление информации о текущем состоянии ваших аккаунтов в ЕЛК ЖКХ. Введение @ TODO @ Установка Посредство

Alexander Ryazanov 27 Nov 05, 2022
A Python program that makes it easy to manage modules on a CircuitPython device!

CircuitPython-Bundle-Manager-v2 A Python program that makes it easy to manage modules on a CircuitPython device! The CircuitPython Bundle Manager v2 i

Ckyiu 1 Dec 18, 2021
Play music on Raspberry Pi Pico Without CPU involvement

MicroPython_PIO_Music_DMA Play music on Raspberry Pi Pico Without CPU involvement This is based on PIOBeep (https://github.com/benevpi/pico_pio_buzz)

3 Nov 27, 2022
A flexible data historian based on InfluxDB, Grafana, MQTT and more. Free, open, simple.

Kotori Telemetry data acquisition and sensor networks for humans. Documentation: https://getkotori.org/ Source Code: https://github.com/daq-tools/koto

83 Nov 26, 2022
Kwcpu - An unobtrusive CPU meter that fits in the default Windows 11 taskbar. Supports up to 32 cores.

kwcpu An unobtrusive CPU meter that fits in the default Windows 11 taskbar. Supports up to 32 cores. kwcpu is provided as a Rainmeter skin. By default

Jay Oster 2 Nov 07, 2022
This is the remake of the program PYOBD. It works on Python3 and all new libraries. It was tested on Linux, Windows, and it should work on MAC too.

This is the remake of the program PYOBD. It works on Python3 and all new libraries. It was tested on Linux, Windows, and it should work on MAC too. You just need an ELM327 USB or bluetooth device and

127 Jan 06, 2023