Skip to main content

Python bindings for dm_robotics/cpp/controllers

Project description

DM Robotics: Controllers Library (Python)

Contents:

Cartesian 6D to Joint Velocity Mapper

Python bindings for dm_robotics/controllers/lsqp/cartesian_6d_to_joint_velocity_mapper.

This module consists of two classes:

  • cartesian_6d_to_joint_velocity_mapper.Parameters
  • cartesian_6d_to_joint_velocity_mapper.Mapper

The mapper solves a constrained linear least-squares optimization problem at every iteration to compute the joint velocities that best achieve the desired Cartesian 6D velocity of an object.

In its most basic configuration, it computes the joint velocities that achieve the desired Cartesian 6d velocity with singularity robustness. In addition, this mapper also supports the following functionality:

  • Nullspace control can be enabled to bias the joint velocities to a desired value without affecting the accuracy of the resultant Cartesian velocity;
  • Collision avoidance can be enabled between any two MuJoCo geoms;
  • Limits on the joint positions, velocities, and accelerations can be defined to ensure that the computed joint velocities do not result in limit violations.

Please refer to dm_robotics/controllers/lsqp/cartesian_6d_to_joint_velocity_mapper.h or the class docstrings for more information.

Dependencies:

  • dm_robotics/least_squares_qp
  • dm_robotics/controllers
  • dm_control

Usage

from dm_control import mujoco
from dm_control.mujoco.wrapper.mjbindings import enums
from dm_robotics.controllers import cartesian_6d_to_joint_velocity_mapper

# Initialize simulation. Assumes velocity controlled robot.
# physics.data.ctrl[:] is an array of size 7 that corresponds to the commanded
# velocities of the joints with IDs 7, 8, 9, 10, 12, 13, 14.
physics = mujoco.Physics(...) # Create MuJoCo physics.

# Create mapper parameters.
params = cartesian_6d_to_joint_velocity_mapper.Parameters()
#
# Set model parameters.
params.model = physics.model
params.joint_ids = [7, 8, 9, 10, 12, 13, 14]  # MuJoCo joint IDs being controlled.
params.object_type = enums.mjtObj.mjOBJ_SITE  # MuJoCo object being controlled.
params.object_name = "end_effector"  # name of MuJoCo object being controlled.
params.integration_timestep = 0.005  # Amount of time the joint velocities will be executed for.
#
# Enable joint position limit constraint. Limits are read automatically from the
# model.
params.enable_joint_position_limits = True
params.joint_position_limit_velocity_scale = 0.95
params.minimum_distance_from_joint_position_limit = 0.01  # ~0.5deg.
#
# Enable joint velocity limits.
params.enable_joint_velocity_limits = True
params.joint_velocity_magnitude_limits = [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5]
#
# Enable joint acceleration limits.
params.enable_joint_acceleration_limits = True
params.remove_joint_acceleration_limits_if_in_conflict = True
params.joint_acceleration_magnitude_limits = [10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0]
#
# Enable collision avoidance between the following geoms:
#   * "gripper" and "base_link"
#   * "base_link" and "floor"
#   * "link1" and "floor"
#   * "gripper" and "floor"
#   * "link1" and "link4"
#   * "link1" and "link5"
#   * "link1" and "link6"
#   * "link2" and "link4"
#   * "link2" and "link5"
#   * "link2" and "link6"
# Note that collision avoidance will not be enabled for a pair of geoms if they
# are attached to the same body or are attached to bodies that have a
# parent-child relationship.
params.enable_collision_avoidance = True
params.collision_avoidance_normal_velocity_scale = 0.5
params.minimum_distance_from_collisions = 0.01
params.collision_detection_distance = 0.3
params.collision_pairs = [(["gripper"], ["base_link"]),
                          (["base_link", "link1", "gripper"], ["floor"]),
                          (["link1", "link2"], ["link4", "link5", "link6"])]
#
# Numerical stability parameters.
params.check_solution_validity = True
params.solution_tolerance = 1e-3
params.regularization_weight = 1e-2
params.enable_nullspace_control = True
params.return_error_on_nullspace_failure = False
params.nullspace_projection_slack = 1e-7

# Create mapper.
mapper = cartesian_6d_to_joint_velocity_mapper.Mapper(params)

# Compute joint velocities and apply them to the joint velocity actuator
# commands at every step.
while True:
  # The nullspace bias is often chosen to be a velocity towards the mid-range of
  # the joints, but can be chosen to be any 7D joint velocity vector.
  nullspace_joint_velocity_bias = get_nullspace_bias()
  target_cartesian_velocity = get_end_effector_target_velocity()
  solution = mapper.compute_joint_velocities(physics.data, target_velocity,
                                             nullspace_bias)
  physics.data.ctrl[:] = solution
  physics.step()

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distributions

No source distribution files available for this release.See tutorial on generating distribution archives.

Built Distributions

If you're not sure about the file name format, learn more about wheel file names.

dm_robotics_controllers-0.10.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl (4.0 MB view details)

Uploaded CPython 3.12manylinux: glibc 2.17+ x86-64

dm_robotics_controllers-0.10.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl (4.0 MB view details)

Uploaded CPython 3.11manylinux: glibc 2.17+ x86-64

dm_robotics_controllers-0.10.0-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl (4.0 MB view details)

Uploaded CPython 3.10manylinux: glibc 2.17+ x86-64

dm_robotics_controllers-0.10.0-cp39-cp39-manylinux2014_x86_64.manylinux_2_17_x86_64.whl (4.0 MB view details)

Uploaded CPython 3.9manylinux: glibc 2.17+ x86-64

File details

Details for the file dm_robotics_controllers-0.10.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl.

File metadata

File hashes

Hashes for dm_robotics_controllers-0.10.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl
Algorithm Hash digest
SHA256 eca7b396c1420106c46cf9ee77c48c3e9b84a0fa71d2e7d067af1bf33ac126e7
MD5 e0ea7825c74408ff694ea1d887915e2d
BLAKE2b-256 d095de35b4439120714c758f61ac7455c4f4eac3151a20d617562c93b384559b

See more details on using hashes here.

File details

Details for the file dm_robotics_controllers-0.10.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl.

File metadata

File hashes

Hashes for dm_robotics_controllers-0.10.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl
Algorithm Hash digest
SHA256 37a9f89811b047631a75449d487eda683bf76d8433399b02220cf66b5ea436ee
MD5 82b7e6947eca099b1e49239b3b601e82
BLAKE2b-256 7a087de1948c005fa82e56c157b68532446c2dac80be6d25766642cf65cdc833

See more details on using hashes here.

File details

Details for the file dm_robotics_controllers-0.10.0-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl.

File metadata

File hashes

Hashes for dm_robotics_controllers-0.10.0-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl
Algorithm Hash digest
SHA256 e18d9b923fc5dce3ac4bc6dc77da3c8a1f6e6e6157ad06f9bd10f4794ad7562d
MD5 ff5d3ef9b3cad0b08117e18fa6c8df3e
BLAKE2b-256 54d9bd069c50c162be9796d1b41c9c456f8081a59437b45001e4ad3301d41d7d

See more details on using hashes here.

File details

Details for the file dm_robotics_controllers-0.10.0-cp39-cp39-manylinux2014_x86_64.manylinux_2_17_x86_64.whl.

File metadata

File hashes

Hashes for dm_robotics_controllers-0.10.0-cp39-cp39-manylinux2014_x86_64.manylinux_2_17_x86_64.whl
Algorithm Hash digest
SHA256 5dc608afd3145e05d4d2648f463e167a0179c8b7e6573a4e6dd2a738a2a71f21
MD5 7388aa92fb7478410fbcc7f1d08680d5
BLAKE2b-256 22d16b45ac913c5119220f461134c8675d54c59a1ccedb5f1118f12fb95e6502

See more details on using hashes here.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page