Jeremy's Robotics Library
Project description
Jrl
Jrl ('Jeremy's robotics library') is a robotics library containing robot models for popular robots as well as efficient, pytorch based parallelized implementations of forward kinematics, inverse kinematics, and robot-robot + robot-environment collision checking. Robot models include (run with scripts/visualize_robot.py
to view):
- Franka Panda
- Iiwa 7dof manipulator
- Fetch 8dof mobile manipulator
Available operations include (all part of the Robot
class):
forward_kinematics_batch()
: batched forward kinematicsjacobian_batch_pt()
: batched manipulator jacobian calculation (change of the end effector's pose w.r.t. each joint angle)inverse_kinematics_single_step_levenburg_marquardt()
: computes a single batched inverse kinematics step using Levenburg-Marquardt optimizationinverse_kinematics_single_step_batch_pt()
: computes a single batched inverse kinematics step using the traditional jacobian pseudo-inverse methodself_collision_distances_batch()
: batched self-collision distance calculationself_collision_distances_jacobian_batch()
: batched calculation of the jacobian of the pair-wise self-collision distances w.r.t. joint anglesenv_collision_distances_batch()
: batched self-environment distance calculationenv_collision_distances_jacobian_batch()
: batched calculation of the jacobian of the self-environment distances w.r.t. joint angles
Quickstart code. This script will load a Panda robot model and then run forward and inverse kinematics on randomly sampled configs. See demo.py for the complete script, which includes robot-robot and robot-environment collision checking.
from jrl.robots import Panda
from jrl.evaluation import pose_errors_cm_deg
import torch
def assert_poses_almost_equal(poses_1, poses_2):
pos_errors_cm, rot_errors_deg = pose_errors_cm_deg(poses_1, poses_2)
assert (pos_errors_cm.max().item() < 0.01) and (rot_errors_deg.max().item() < 0.1)
robot = Panda()
joint_angles, poses = robot.sample_joint_angles_and_poses(n=5, return_torch=True) # sample 5 random joint angles and matching poses
# Run forward-kinematics
poses_fk = robot.forward_kinematics_batch(joint_angles)
assert_poses_almost_equal(poses, poses_fk)
# Run inverse-kinematics
ik_sols = joint_angles + 0.1 * torch.randn_like(joint_angles)
for i in range(5):
ik_sols = robot.inverse_kinematics_single_step_levenburg_marquardt(poses, ik_sols)
assert_poses_almost_equal(poses, robot.forward_kinematics_batch(ik_sols))
Note: This project uses the w,x,y,z
format for quaternions.
Installation
Recommended: clone the repo and install with pip
git clone https://github.com/jstmn/jrl.git && cd jrl/
pip install -e .
# or:
pip install -e ".[dev]"
Second option: Install from pypi (not recomended - the pypi version will likely be out of date until this project hardens)
pip install jrl
Project details
Release history Release notifications | RSS feed
Download files
Download the file for your platform. If you're not sure which to choose, learn more about installing packages.
Source Distribution
Built Distribution
File details
Details for the file jrl-0.0.9.tar.gz
.
File metadata
- Download URL: jrl-0.0.9.tar.gz
- Upload date:
- Size: 29.2 MB
- Tags: Source
- Uploaded using Trusted Publishing? No
- Uploaded via: twine/4.0.2 CPython/3.8.10
File hashes
Algorithm | Hash digest | |
---|---|---|
SHA256 | af8fba9d72c7c967854e21292bafe2227fd1f1d869c52920409982a81030db00 |
|
MD5 | 747528541a2007e2155689a9d2a646db |
|
BLAKE2b-256 | 8007c200489bcb2c321ac7d210f5b85bd6b74ca388ff4fb3704b1115a53622a1 |
File details
Details for the file jrl-0.0.9-py3-none-any.whl
.
File metadata
- Download URL: jrl-0.0.9-py3-none-any.whl
- Upload date:
- Size: 29.2 MB
- Tags: Python 3
- Uploaded using Trusted Publishing? No
- Uploaded via: twine/4.0.2 CPython/3.8.10
File hashes
Algorithm | Hash digest | |
---|---|---|
SHA256 | dd697de6e80812dc802e02e54342ff21552a0915cccd993236806f4bd0d4f127 |
|
MD5 | 773f64310b634aef03596b426fdcbdc1 |
|
BLAKE2b-256 | 05934a8a3b9c67eecac4fb9fd9cd6414a2bf3d93d0aae2888a1cad16b9692f75 |