Giter Club home page Giter Club logo

abr_control's Introduction

image

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. Example scripts showing how to use the ABR Control package are in the docs/examples folder.

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
pip install -e .

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

Optional Installation

Mujoco

To run Mujoco simulations, you will need the mujoco and mujoco-python-viewer packages installed. You can either pip install these yourself or run the repo install with pip install -e .[optional]. Additionally, in Ubuntu 20.04 you may need:

sudo apt install libomesa6-dev
sudo apt install libglew-dev
sudo apt install patchelf

Pygame

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

pip install pygame

CoppeliaSim

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

ABR Jaco2

In addition to simulation of the Kinova Jaco2 in CoppeliaSim and Mujoco, we have an API for controlling the real arm. For installation instructions, see the ABR_Jaco2 repository.

Usage

The ABR Control repo is comprised of four parts: 1) arms, 2) controllers, 3) path planners, and 4) interfaces.

1a) Arms: Config files for CoppeliaSim, Pygame, or real arms

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 a new config. For CoppeliaSim, Pygame, or a real arm, the config must contain 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.

1b) Arms: Config files for 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 <geom> 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.

For a detailed walk-through of how the ur5 mujoco model was built, see this tutorial

1c) Arms: Instantiation and transforms

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. There is also a base config class written for mujoco that has wrappers for these function so that they can be accessed in the same way. This way your code should work between various simulators with minimal changes required. The different config files can be instantiated as:

Pygame and CoppeliaSim:

from abr_control.arms import jaco2 as arm

# ur5, onelink, twolink, and threelink also available to import
robot_config = arm.Config()

Mujoco:

from abr_control.arms import mujoco_config as arm

# 'ur5', 'onelink', 'twolink', and 'threelink' also available as arm_model's
arm_model = 'jaco2'
robot_config = arm.MujocoConfig(arm_model)

ABR Jaco2 (real arm):

import abr_jaco2
robot_config = abr_jaco2.Config()

The transforms can then be accessed from the instantiated robot 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

1d) Arms: Cython for real-time control

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.

image

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 (OSC), 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. Additionally, the OSC can be set to control any combination of the 6 controllable degrees of freedom of the end-effector. These are the end-effectors x, y, z position, and a, b, g orientation.

There is also an implementation of nonlinear adaptive control in the controllers/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. See the docs/examples folder for various use cases and examples of these controllers.

3a) Path Planners: generating a path

In the controllers/path_planners folder there is a generalized path planner that can be used in conjunction with the controllers to provide filtered via points to your target state. This can greatly improve the stability of an arm's motion. The path planner can generate up to a 12 dimensional path that follows velocity and acceleration limitations. The path planner determines these limits and the shape of the path to take by the position and velocity profiles passed on __init__.

The path planner has a generate_path() function that takes in start and target positions, and a maximum velocity to travel. Optionally, start and target velocities (default 0 and 0) and orientations can be passed in. The path planner will generate a trajectory from your desired start to target positions (and optionally orientations). It will also discretize the path over time such that it will be moving at the set start velocity at the beginning of the path, and will reach your target position and orientation while moving at your target velocity in that moment. The path planner will use the velocity profile to accelerate from your start_velocity up to your max_velocity, and back down to your target_velocity. If the path to travel is too short to reach the maximum velocity, the path planner will reach the maximum velocity it can before it needs to begin decelerating to converge to your target state, while maintaining the desired path shape. For longer paths the path planner will output a constant velcoity of max_velocity once that speed is reached, until it is time to decelerate.

The orientation path is planned using spherical linear interpolation (SLERP) to generate a set of orientations from a start to a target orientation. The time profile will match that of the path planner (ie: a linear velocity profile will have a linear step in orientation over time, with a constant change in orientation, whereas a gaussian velocity profile 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.)

3b) Path Planners: position profiles

The position profiles can be thought of as the general shape the path should follow. They contain a step(t) function that outputs a 3D position in the domain of [0, 1]. [0, 0, 0] and [1, 1, 1] are restricted to be the start and end of the path, which correspond to times 0 and 1, respectively. For a straight-line path this would be a straight line from [0, 0, 0] to [1, 1, 1]. The path planner will rotate the position profile to align with the direction of your target_position-start_position, then translate and transform it to start and end at the start and target positions.

image

More complex shapes are available such as ellipse and sin curves are readily available, and custom ones can be added with relative ease. For example, an ellipse profile can be followed, with an additional parameter than can adjust the stretching along the horizontal axis

image

3c) Path Planners: velocity profiles

The velocity profiles are decoupled from the position profiles so that arbitrary low frequency shapes can be defined, and the planned path will follow those shapes while maintaining physically limited velocity and acceleration profiles. The velocity profiles have a generate() function that outputs a list of velocities from a set start to target velocity. The various velocity_profiles vary in their acceleration curves. For example, the velocity_profiles.Linear() class has a constant acceleration from start to target.

image

In comparison, the velocity_profiles.Gaussian() class has a smoothly changing velocity that follows a gaussian curve.

image

4) 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 four files looks like:

import numpy as np

from abr_control.arms import ur5 as arm
from abr_control.controllers import OSC, Damping
from abr_control.controllers.path_planners import PathPlanner
from abr_control.controllers.path_planners.position_profiles import Linear
from abr_control.controllers.path_planners.velocity_profiles import Gaussian
from abr_control.interfaces import CoppeliaSim
from abr_control.utils import transformations

# Sim step size
dt = 0.005

# Initialize our robot config
robot_config = arm.Config()

# Damp the movements of the arm
damping = Damping(robot_config, kv=10)

# Create opreational space controller controlling all 6 DOF
ctrlr = OSC(
    robot_config,
    kp=100,  # position gain
    ko=250,  # orientation gain
    null_controllers=[damping],
    vmax=None,  # [m/s, rad/s]
    # control all DOF [x, y, z, alpha, beta, gamma]
    ctrlr_dof=[True, True, True, True, True, True],
)

# Create our interface
interface = CoppeliaSim(robot_config, dt=dt)
interface.connect()

# Create a path planner with a linear shape and gaussian velocity curve
path_planner = PathPlanner(
    pos_profile=Linear(),
    vel_profile=Gaussian(dt=dt, acceleration=2)
)

# Get our starting state
feedback = interface.get_feedback()
hand_xyz = robot_config.Tx("EE", feedback["q"])
starting_orientation = robot_config.quaternion("EE", feedback["q"])

# Generate a target
target_orientation = np.random.random(3)
target_orientation /= np.linalg.norm(target_orientation)
# convert our orientation to a quaternion
target_orientation = [0] + list(target_orientation)
target_position = [-0.4, -0.3, 0.6]

starting_orientation = transformations.euler_from_quaternion(
    starting_orientation, axes='rxyz')

target_orientation = transformations.euler_from_quaternion(
    target_orientation, axes='rxyz')

# Generate our 12D path
path_planner.generate_path(
    start_position=hand_xyz,
    target_position=target_position,
    start_orientation=starting_orientation,
    target_orientation=target_orientation,
    start_velocity=0,
    target_velocity=0,
    max_velocity=2
)

count = 0

# Step through the planned path, with the OSC trying to
# bring the end-effector to the filtered target state
while count < path_planner.n_timesteps:
    # get arm feedback
    feedback = interface.get_feedback()
    hand_xyz = robot_config.Tx("EE", feedback["q"])

    next_target = path_planner.next()
    pos = next_target[:3]
    vel = next_target[3:6]
    orient = next_target[6:9]

    u = ctrlr.generate(
        q=feedback["q"],
        dq=feedback["dq"],
        target=np.hstack([pos, orient]),
        target_velocity=np.hstack([vel, np.zeros(3)])
    )

    # apply the control signal, step the sim forward
    interface.send_forces(u)

    count += 1

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. See Section 1 above for the difference in arm instantiation for a Mujoco sim.

Examples

The ABR Control repo comes with several examples that demonstrate the use of the different interfaces and controllers. You can find the examples in the docs/examples folder.

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.

abr_control's People

Contributors

drasmuss avatar filrocha avatar hunse avatar p3jawors avatar studywolf avatar tbekolay avatar wesleymth avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

abr_control's Issues

Error

ModuleNotFoundError: No module named 'mujoco_viewer'. How to find the revelant file

Import pygame for examples

Should add a try except in the pygame examples to let the user know that pygame has to be manually installed to run the examples in the case that it's missing.

Control of two robots

Thank you for your useful repo. We are trying to perform the assembly experiments. Is it possible to control two robots, for example, two ur5 robots, at the same time?

AttributeError: 'MjViewer' object has no attribute 'exit'

I have installed mujoco200 and mujoco-py2.0.
But when I run the /example/Mujoco, there is an error in this code:
'if interface.viewer.exit:'
.......

So I can't run any Mujoco examples for all they have this code in the first 'While'.....

I have searched it online, may it be the prolem of version of mujoco-py ?
For there is not mujoco-py‘s and mujoco's version mentioned.

Can I download those mesh and texture files directly?

Hello, I want to run some examples in Vrep, and I have to 'Download mesh and texture files to run sim'. But I am in China, and I always get a 'Connection time out' error when I am trying to download them.

I want to know if you can give all the links of the mesh and texture files so that I can download beforehand(it is more convenient for me because I could use a lot of network tools to download them), and also could you tell me where to put those files if I download them by myself? Thanks.

config.py file for UR5e

Hi. Thank you for your work. I am using abr_control to control UR5e robots, but do not actually find a config.py file for them. Would anyone please share that or could you please let me know how to create one for the UR5e robots?

Thank you!

example names

having examples named "position control" is probably confusing, since we're doing force control of position, not just position control

thanks + pointer to other robot control library

@studywolf I've been a reader of your blog for quite some time and first I wanted to thank you for all the detailed and informative posts you've written. I saw your recent post about the motion control library. https://studywolf.wordpress.com/tag/vrep/

I wanted to point you to another set of libraries that go together which I've been using and have found to be quite good for similar purposes:
https://github.com/jrl-umi3218/Tasks
https://github.com/jrl-umi3218/SpaceVecAlg
https://github.com/jrl-umi3218/RBDyn
https://github.com/jrl-umi3218/Eigen3ToPython

This is really just an FYI which incorporates other interesting control approaches and also has been integrated with v-rep in various projects. Hopefully this is more useful or interesting than disruptive, but feel free to close. Thanks! :-)

Import redis in dynamics_adaptation

Should set this up as an option and use a try except in the case that the user wants the functionality. At the moment you get an error if redis isn't installed, but it shouldn't be required.

How to create manipulator config files

Hello, I have a new robot config information with urdf format file and D-H parameters, I wish to know how to convert it into config files of this project? The variables in config.py is confusing, can you tell me how to calculate them?

TypeError: 'numpy.ndarray' object is not callable

my code is demo in readme:

from abr_control.arms import jaco2
from abr_control.controllers import OSC
from abr_control.interfaces import Mujoco
import numpy as np


robot_config = jaco2.Config()
interface = Mujoco(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()

an error occured at line 224 of basic_config.g(). The traceback is:

Traceback (most recent call last):
  File "/home/room525/Desktop/code/abr_control/demo.py", line 19, in <module>
    u = ctrlr.generate(
  File "/home/room525/Desktop/code/abr_control/abr_control/controllers/osc.py", line 301, in generate
    u -= self.robot_config.g(q=q)
  File "/home/room525/Desktop/code/abr_control/abr_control/arms/base_config.py", line 224, in g
    return np.array(self._g(*parameters), dtype="float32").flatten()
TypeError: 'numpy.ndarray' object is not callable

the problem is caused by self._g(*parameters), where self._g is a np.ndarray [0. 0. 0. 0. 0. 0.], the parameters is joint angle that's a tuple. Does self._g(*parameters)mean self._g plus parameters?

AttributeError: 'MjViewer' object has no attribute 'exit'

Hello everyone, I met a problem recently when I run the bar control example of jaco2 for Mujoco platform. When I run the program "position_joint_control.py", all my environment variables and configuration are right. Howver, on Pycharm, the terminal shows the problem as below:

To download mujoco stl files, you need to "pip install requests"
Creating window glfw
MuJoCo session created

Simulation starting...

Traceback (most recent call last):
  File "/home/shine/abr_control/docs/examples/Mujoco/position_joint_control.py", line 43, in <module>
    if interface.viewer.exit:
AttributeError: 'MjViewer' object has no attribute 'exit'

MuJoCO session closed...
Simulation terminated...

The simulation windows seems crash out and I didn't see anything on that. Does anyone meet the same problem? Thanks!

Additionally, I see someone came up with the same question a few years ago, I followed the suggestions but it seems doesn't work for current Mujoco or mujoco-py. That makes me feel confused.

Non-linear trajectory issue

Hi,

I'm using the attached mjcf to play with the examples/Mujoco/force_osc_xyz_linear_path_gaussian_velocity.py . But I found the trajectory of the end-effector is not linear as the figure shows. My questions are:

  1. Is there anyway to fix this issue?
  2. If it's impossible, I was wondering if you know any robotiq85 gripper working fine with the built-in ur5 of abr_control?
  3. May I know the metrics used in this project?

eef traj:
Screenshot from 2023-04-26 16-39-11

mjcf xml:
ur5e_gripper.zip

Thank you!

PyPI release

It would be nice to have a PyPI release for this repo so that it can be pip installed.

ImportError: No module named joint0[0,0,0]_Tx.wrapper_module_0

Hi there,

I have been following your work recently (Play around with the sympy lib and a UR3 arm). Now I was trying to use this abr_control library, I made it work with the UR3 model and the first time it runs kind of fine. I take about 10 minutes computing every... kinda slow but anyway it works. But when I try to run it again I got an error about loading a saved function. I tried with the pygame example to see if it was not a problem with my custom model, but I got the same thing after trying to run the example a 2nd time:

Traceback (most recent call last): File "reaching_sliding.py", line 30, in <module> interface.connect() File "/home/cambel/dev/abr_control/abr_control/interfaces/ipygame.py", line 87, in connect self.arm_sim.connect() File "/home/cambel/dev/abr_control/abr_control/arms/threejoint/arm_sim.py", line 54, in connect self._update_state() File "/home/cambel/dev/abr_control/abr_control/arms/threejoint/arm_sim.py", line 121, in _update_state self._position() File "/home/cambel/dev/abr_control/abr_control/arms/threejoint/arm_sim.py", line 109, in _position for ii in range(self.robot_config.N_JOINTS)] File "/home/cambel/dev/abr_control/abr_control/arms/base_config.py", line 362, in Tx self._Tx[funcname] = self._calc_Tx(name, x=x) File "/home/cambel/dev/abr_control/abr_control/arms/base_config.py", line 754, in _calc_Tx Tx, Tx_func = self._load_from_file(filename, lambdify) File "/home/cambel/dev/abr_control/abr_control/arms/base_config.py", line 188, in _load_from_file filename + '.' + saved_file) File "/usr/lib/python2.7/importlib/__init__.py", line 37, in import_module __import__(name) ImportError: No module named joint0[0,0,0]_Tx.wrapper_module_0

It seems to be unable to find the saved function.

3D model files missing

Hi, I am a new user of abr_control. The examples in the directories of PyGame and VREP both work well. However, when I execute python3 dynamics_adaptation_osc.py, I receive the following error:
Screenshot from 2019-10-15 14-41-52
And indeed there isn't any 3D model file in meshes directory. Where can I get jaco2's model files?

MujocoConfig Error

AttributeError: type object 'MujocoConfig' has no attribute 'Config'

from abr_control.arms.mujoco_config import MujocoConfig as arm

# 'ur5', 'onelink', 'twolink', and 'threelink' also available as arm_model's
arm_model = 'jaco2'
robot_config = arm.Config(arm_model)

Question for the hand/gripper control

Hello everyone, recently I tried this lib to implement In our robot arm simulation on Mujoco I didn't find any example for the gripper control such as Jaco2 and don't know how to do that Can anyone give some suggestions for that or share what you did for your robot simulation? Thanks!

xyz_offset argument with problems

I've added an ur5 arm on a mobile robot. Because of that i need to constantly update its base position. But when I use the OSC.generate and robot_config.Tx with the specific xyz offset. It returns a different value that is supposed to be. For example:

base = interface.get_xyz("UR5_link0_visible")
result: Base is:  [-9.712021827697754, 1.791999101638794, 0.16733066737651825]

start = robot_config.Tx("EE", feedback["q"], x= np.array(base))
result: start is:  [-0.33954067  1.79179413 -8.71078803]

The vrep scenes with Jaco2 have six joints, but the abr_control uses only five. This is expected?

Hi!, your repository is amazing. Thanks for sharing!

I realize that the configurations space of Jaco2 arm from abr_control module is a vector 5x1. However, in the vrep scene, Jaco2 have six joints.

from abr_control.arms import jaco2 as arm
from abr_control.controllers import OSC
from abr_control.interfaces import VREP
import numpy as np

robot_config = arm.Config(use_cython=True)
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])
interface = VREP(robot_config)

interface.connect()

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
    q = feedback['q']
    print(q.shape)
    u = ctrlr.generate(
        q=feedback['q'],
        dq=feedback['dq'],
        target=np.hstack([target_xyz, target_orientation]))
    interface.send_forces(u)  # send forces and step VREP sim forward
interface.disconnect()

Output:

Connected to VREP remote API server

(5,)

Expected:

(6,)

Why q = feedback['q'] returns a vector 5x1 if the robot have six joints?

Thanks for your time!

Att

Juan

What is the effect of dt in your expressions?

I can see on your examples you set the dt value in order to connect and set time step of the simulation. But when I designedly increase the dt value, higher is the joint torque value (u) and consequently the control fails at higher dt value. However, no step time is used on your equations, besides when you set up the connection to CoppeliaSim.

My main objective by asking this is to use your repository via ROS, and controls UR5 robot arm at CoppeliaSim using ROS interface. By doing this it is not possible to force a time step, and both (CoppeliaSim and ROS) will run asynchronously.

Is that a way to control according to dt, or I need a powerful computer to run both as fast as possible, in order to indirectly generate a lower dt value? (Also thinking in real life robot arm control)

Other arms with ABR_Control

Currently, the models support OSC controllers for Jaco and UR5
Is there a plan to do this for other robot arms, Sawyer or Franka Emika.

Further doing the same for these arms in Coppelia and Mujoco?

Mujoco install issues I encountered.

For starters, I did not use conda. I worked with pip install git+https://github.com/abr/abr_control

This installs the repo in your python package location.

Issue 1. That method does not automatically pull the robot XML files in the arms folder(At least for me). So whichever arm you want, I came here(to the repo) and copied the XML file into the respective arm folder in your system.

Issue 2. When working with Mujoco, the demo files initially gave out an error for me saying AttributeError: 'MjViewer' object has no attribute 'exit'

This can be quickly fixed with commenting out the following lines of code.
if interface.viewer.exit: glfw.destroy_window(interface.viewer.window) break

I'm not sure if the above is the best solution, but it works.

Issue 3. this repo doesn't seem to have the end effectors for anything but the jaco2, but how do we manipulate the EE? And is there anywhere we can find existing XML files for UR5 End effectors?

Inverse kinematic for Mujoco

Hi, I wanted to ask if your implementations also allow inverse kinematic for mujoco.

I am interested in getting joints' values (MjData.qpos) for a given the desired end-effector pose, and not necessarily wish to move the arm to that position (similar to PyBullet's inverse kinematic api).

TypeError: argument is not an mpz

Hi, friends, i installed abr_control and run the code below:

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

robot_config = jaco2.Config()
ctrlr = OSC(robot_config)
interface = VREP(robot_config)

interface.connect()

target_xyz = [.2, .2 .5]  # in metres
for ii in range(1000)
    feedback = interface.get_feedback()  # returns a dictionary with q, dq
    u = ctrlr.generate(feedback['q'], feedback['dq'], target_xyz)
    interface.send_forces(u)  # send forces and step VREP sim forward

interface.disconnect()

I got this error:
TypeError: argument is not an mpz
Hope to find a solution~

error occurs when calculation of 'C'

When I run file ' position_control_sliding.py' to test, an error occurs as follows:
'UnicodeDecodeError: 'utf-8' codec can't decode byte 0xc3 in position 908: invalid continuation byte', which is in file base_config.py Line 769 in _calc_C.
I compare the calculation of J, M, G, it seems that only calculation C is nor right.

Import nengo_extras in dynamics_adaptation

try except not set up correctly. At the moment if nengo_extras isn't installed an exception is raised at the start of the module, but this should be moved to where nengo_extras would be used. It is only required when doing bootstrap learning, which is not very often.

ask for reference about the controllers

I have seen there are several different controllers in the "abr_control/abr_control/controllers/", such as OSC and sliding et al. Could you give me some references related to your controllers? Many thanks for your kindly help :-D

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.