Scikit-Robot – A Flexible Framework for Robot Control in Python

Scikit-Robot is a simple pure-Python library for loading, manipulating, and visualizing URDF files and robot specifications. For example, here’s a rendering of a PR2 robot moving after being loaded by this library.

_images/pr2.gif

Installation and Setup Guide

Python Installation

This package is pip-installable for any Python version. Simply run the following command:

pip install scikit-robot

Installing in Development Mode

If you’re planning on contributing to this repository, please see the Development Guide.

Usage Examples

This page documents several simple use cases for you to try out. For full details, see the API Reference, and check out the full class reference for RobotModel.

Loading from a File

You can load a URDF from any .urdf file, as long as you fix the links to be relative or absolute links rather than ROS resource URLs.

>>> import skrobot
>>> robot_model = skrobot.models.urdf.RobotModelFromURDF(urdf_file=skrobot.data.pr2_urdfpath())

Visualization

>>> viewer = skrobot.viewers.TrimeshSceneViewer(resolution=(640, 480))
>>> viewer.add(robot_model)
>>> viewer.show()

If you would like to update renderer:

>>> viewer.redraw()

Inverse Kinematics

First, set the initial pose. Note that the position of the prismatic joint is in [m] and angles of rotational joints are in [rad].

>>> robot_model.torso_lift_joint.joint_angle(0.05)
>>> robot_model.l_shoulder_pan_joint.joint_angle(60 * 3.14/180.0)
>>> robot_model.l_shoulder_lift_joint.joint_angle(74 * 3.14/180.0)
>>> robot_model.l_upper_arm_roll_joint.joint_angle(70* 3.14/180.0)
>>> robot_model.l_elbow_flex_joint.joint_angle(-120 * 3.14/180.0)
>>> robot_model.l_forearm_roll_joint.joint_angle(20 * 3.14/180.0)
>>> robot_model.l_wrist_flex_joint.joint_angle(-30 * 3.14/180.0)
>>> robot_model.l_wrist_roll_joint.joint_angle(180 * 3.14/180.0)
>>> robot_model.r_shoulder_pan_joint.joint_angle(-60 * 3.14/180.0)
>>> robot_model.r_shoulder_lift_joint.joint_angle(74 * 3.14/180.0)
>>> robot_model.r_upper_arm_roll_joint.joint_angle(-70 * 3.14/180.0)
>>> robot_model.r_elbow_flex_joint.joint_angle(-120 * 3.14/180.0)
>>> robot_model.r_forearm_roll_joint.joint_angle(-20 * 3.14/180.0)
>>> robot_model.r_wrist_flex_joint.joint_angle(-30 * 3.14/180.0)
>>> robot_model.r_wrist_roll_joint.joint_angle(180 * 3.14/180.0)
>>> robot_model.head_pan_joint.joint_angle(0)
>>> robot_model.head_tilt_joint.joint_angle(0)

Next, set move_target and link_list

>>> rarm_end_coords = skrobot.coordinates.CascadedCoords(
...             parent=robot_model.r_gripper_tool_frame,
...             name='rarm_end_coords')
>>> move_target = rarm_end_coords
>>> link_list = [
...     robot_model.r_shoulder_pan_link,
...     robot_model.r_shoulder_lift_link,
...     robot_model.r_upper_arm_roll_link,
...     robot_model.r_elbow_flex_link,
...     robot_model.r_forearm_roll_link,
...     robot_model.r_wrist_flex_link,
...     robot_model.r_wrist_roll_link]

Set target_coords.

>>> target_coords = skrobot.coordinates.Coordinates([0.5, -0.3, 0.7], [0, 0, 0])
>>> robot_model.inverse_kinematics(
...     target_coords,
...     link_list=link_list,
...     move_target=move_target)

API Reference

Coordinates

Coordinates classes

skrobot.coordinates.Coordinates

Coordinates class to manipulate rotation and translation.

skrobot.coordinates.CascadedCoords

Coordinates utilities

skrobot.coordinates.geo.midcoords

Returns mid (or p) coordinates of given two coordinates c1 and c2.

skrobot.coordinates.geo.orient_coords_to_axis

Orient axis to the direction

skrobot.coordinates.base.random_coords

Return Coordinates class has random translation and rotation

skrobot.coordinates.base.coordinates_distance

skrobot.coordinates.base.transform_coords

Return Coordinates by applying c1 to c2 from the left

Quaternion Classes

skrobot.coordinates.quaternion.Quaternion

Class for handling Quaternion.

skrobot.coordinates.dual_quaternion.DualQuaternion

Class for handling dual quaternions and their interpolations.

Models

Robot Model class

skrobot.model.RobotModel

Robot Model classes

You can create use robot model classes. Here is a example of robot models.

Fetch

skrobot.models.fetch.Fetch

Fetch Robot Model.

_images/fetch.png
Kuka

skrobot.models.kuka.Kuka

Kuka Robot Model.

_images/kuka.png
PR2

skrobot.models.pr2.PR2

PR2 Robot Model.

_images/pr2.png

Functions

Utilities functions

skrobot.coordinates.math._wrap_axis

Convert axis to float vector.

skrobot.coordinates.math._check_valid_rotation

Checks that the given rotation matrix is valid.

skrobot.coordinates.math._check_valid_translation

Checks that the translation vector is valid.

skrobot.coordinates.math.triple_product

Returns Triple Product

skrobot.coordinates.math.inverse_rodrigues

Inverse Rodrigues formula Convert Rotation-Matirx to Axis-Angle.

skrobot.coordinates.math.rotation_angle

Inverse Rodrigues formula Convert Rotation-Matirx to Axis-Angle.

skrobot.coordinates.math.make_matrix

Wrapper of numpy array.

skrobot.coordinates.math.random_rotation

Generates a random 3x3 rotation matrix.

skrobot.coordinates.math.random_translation

Generates a random translation vector.

skrobot.coordinates.math.midpoint

Return midpoint

skrobot.coordinates.math.midrot

Returns mid (or p) rotation matrix of given two matrix r1 and r2.

skrobot.coordinates.math.transform

Return transform m v

skrobot.coordinates.math.rotation_matrix

Return the rotation matrix.

skrobot.coordinates.math.rotate_vector

Rotate vector.

skrobot.coordinates.math.rotate_matrix

skrobot.coordinates.math.rpy_matrix

Return rotation matrix from yaw-pitch-roll

skrobot.coordinates.math.rpy_angle

Decomposing a rotation matrix to yaw-pitch-roll.

skrobot.coordinates.math.normalize_vector

Return normalized vector

skrobot.coordinates.math.matrix_log

Returns matrix log of given rotation matrix, it returns [-pi, pi]

skrobot.coordinates.math.matrix_exponent

Returns exponent of given omega.

skrobot.coordinates.math.outer_product_matrix

Returns outer product matrix of given v.

skrobot.coordinates.math.rotation_matrix_from_rpy

Returns Rotation matrix from yaw-pitch-roll angles.

skrobot.coordinates.math.rotation_matrix_from_axis

Return rotation matrix orienting first_axis

skrobot.coordinates.math.rodrigues

Rodrigues formula.

skrobot.coordinates.math.rotation_angle

Inverse Rodrigues formula Convert Rotation-Matirx to Axis-Angle.

skrobot.coordinates.math.rotation_distance

Return the distance of rotation matrixes.

skrobot.coordinates.math.axis_angle_from_matrix

Converts the rotation of a matrix into axis-angle representation.

skrobot.coordinates.math.angle_between_vectors

Returns the smallest angle in radians between two vectors.

Jacobian Functions

skrobot.coordinates.math.sr_inverse

Returns SR-inverse of given Jacobian.

skrobot.coordinates.math.sr_inverse_org

Return SR-inverse of given J

skrobot.coordinates.math.manipulability

Return manipulability of given matrix.

Quaternion Functions

skrobot.coordinates.math.xyzw2wxyz

Convert quaternion [x, y, z, w] to [w, x, y, z] order.

skrobot.coordinates.math.wxyz2xyzw

Convert quaternion [w, x, y, z] to [x, y, z, w] order.

skrobot.coordinates.math.random_quaternion

Generate uniform random unit quaternion.

skrobot.coordinates.math.quaternion_multiply

Return multiplication of two quaternions.

skrobot.coordinates.math.quaternion_conjugate

Return conjugate of quaternion.

skrobot.coordinates.math.quaternion_inverse

Return inverse of quaternion.

skrobot.coordinates.math.quaternion_slerp

Return spherical linear interpolation between two quaternions.

skrobot.coordinates.math.quaternion_distance

Return the distance of quaternion.

skrobot.coordinates.math.quaternion_absolute_distance

Return the absolute distance of quaternion.

skrobot.coordinates.math.quaternion_norm

Return the norm of quaternion.

skrobot.coordinates.math.quaternion_normalize

Return the normalized quaternion.

skrobot.coordinates.math.matrix2quaternion

Returns quaternion of given rotation matrix.

skrobot.coordinates.math.quaternion2matrix

Returns matrix of given quaternion.

skrobot.coordinates.math.quaternion2rpy

Returns Roll-pitch-yaw angles of a given quaternion.

skrobot.coordinates.math.rpy2quaternion

Return Quaternion from yaw-pitch-roll angles.

skrobot.coordinates.math.rpy_from_quat

Returns Roll-pitch-yaw angles of a given quaternion.

skrobot.coordinates.math.quat_from_rotation_matrix

Returns quaternion of given rotation matrix.

skrobot.coordinates.math.quat_from_rpy

Return Quaternion from yaw-pitch-roll angles.

skrobot.coordinates.math.rotation_matrix_from_quat

Returns matrix of given quaternion.

skrobot.coordinates.math.quaternion_from_axis_angle

Return the quaternion from axis angle

skrobot.coordinates.math.axis_angle_from_quaternion

Converts a quaternion into the axis-angle representation.

Geometry functions

skrobot.coordinates.geo.rotate_points

Rotate given points based on a starting and ending vector.

Interfaces

Pybullet Interface

You can use a Pybullet interface using skrobot.

skrobot.interfaces._pybullet.PybulletRobotInterface

Pybullet Interface Class

>>> from skrobot.models import PR2
>>> from skrobot.interfaces import PybulletRobotInterface
>>> import pybullet
>>> client_id = pybullet.connect(pybullet.GUI)
>>> robot_model = PR2()
>>> interface = PybulletRobotInterface(robot_model, connect=client_id)
>>> interface.angle_vector(robot_model.reset_pose())
_images/pybullet_interface.png

Signed distance function (SDF)

SDF classes

skrobot.sdf.SignedDistanceFunction

A base class for signed distance functions (SDFs).

skrobot.sdf.UnionSDF

One can concat multiple SDFs sdf_list by using this class.

skrobot.sdf.BoxSDF

SDF for a box specified by origin and width.

skrobot.sdf.GridSDF

SDF using precopmuted signed distances for gridded points.

skrobot.sdf.CylinderSDF

SDF for a cylinder specified by origin,`radius` and height

skrobot.sdf.SphereSDF

SDF for a sphere specified by origin and radius.

SDF utilities

skrobot.sdf.signed_distance_function.trimesh2sdf

Convert trimesh to signed distance function.

skrobot.sdf.signed_distance_function.link2sdf

Convert Link to corresponding sdf

Planning

Sdf-swept-sphere-based collision checker

skrobot.planner.SweptSphereSdfCollisionChecker

Collision checker between swept spheres and sdf

SQP-based trajectory planner

skrobot.planner.sqp_plan_trajectory

Gradient based trajectory optimization using scipy's SLSQP.

Swept sphere generater

skrobot.planner.swept_sphere.compute_swept_sphere

Compute swept spheres approximating a mesh

Planner utils

skrobot.planner.utils.scipinize

Scipinize a function returning both f and jac

skrobot.planner.utils.set_robot_config

A utility function for setting robot state

skrobot.planner.utils.get_robot_config

A utility function for getting robot state

skrobot.planner.utils.forward_kinematics_multi

Compute fk for multiple feature points

Development Guide

Read this guide before doing development in skrobot.

Setting Up

To set up the tools you’ll need for developing, you’ll need to install skrobot in development mode. Start by installing the development dependencies:

git clone https://github.com/iory/scikit-robot.git
cd scikit-robot
pip install -e .

Running Code Style Checks

We follow PEP 8 and partially OpenStack Style Guidelines as basic style guidelines. Any contributions in terms of code are expected to follow these guidelines.

You can use the autopep8, isort and the flake8 commands to check whether or not your code follows the guidelines. In order to avoid confusion from using different tool versions, we pin the versions of those tools. Install them with the following command (from within the top directory of the Chainer repository):

$ pip install hacking pytest autopep8 isort

And check your code with:

$ autopep8 path/to/your/code.py
$ flake8 path/to/your/code.py

autopep8 can automatically correct Python code to conform to the PEP 8 style guide:

$ autopep8 --in-place path/to/your/code.py

isort can automatically correct import order:

$ cd scikit-robot && isort path/to/your/code.py

For more information, please see the flake8 documentation.

Running Tests

This project uses pytest, the standard Python testing framework. Their website has tons of useful details, but here are the basics.

To run the testing suite, simply navigate to the top-level folder in scikit-robot and run the following command:

pytest -v tests

You should see the testing suite run. There are a few useful command line options that are good to know:

  • -s - Shows the output of stdout. By default, this output is masked.

  • --pdb - Instead of crashing, opens a debugger at the first fault.

  • --lf - Instead of running all tests, just run the ones that failed last.

  • --trace - Open a debugger at the start of each test.

You can see all of the other command-line options here.

By default, pytest will look in the tests folder recursively. It will run any function that starts with test_ in any file that starts with test_. You can run pytest on a directory or on a particular file by specifying the file path:

pytest -v tests/skrobot_tests/coordinates_tests/test_math.py

Building Documentation

To build scikit-robot’s documentation, go to the docs directory and run make with the appropriate target. For example,

cd docs/
make html

will generate HTML-based docs, which are probably the easiest to read. The resulting index page is at docs/build/html/index.html. If the docs get stale, just run make clean to remove all build files.

Indices and tables