pydrake.common

Bindings for //common:common

pydrake.common.CalcProbabilityDensity(*args, **kwargs)

Overloaded function.

  1. CalcProbabilityDensity(distribution: pydrake.common.RandomDistribution, x: numpy.ndarray[numpy.float64[m, 1]]) -> float

Calculates the density (probability density function) of the multivariate distribution.

Parameter distribution:

The distribution type.

Parameter x:

The value of the sampled vector. $Note:

When instantiating this function, the user needs to explicitly pass in the scalar type, for example CalcProbabilityDensity<double>(…), the compiler might have problem to deduce the scalar type automatically.

  1. CalcProbabilityDensity(distribution: pydrake.common.RandomDistribution, x: numpy.ndarray[object[m, 1]]) -> Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> >

Calculates the density (probability density function) of the multivariate distribution.

Parameter distribution:

The distribution type.

Parameter x:

The value of the sampled vector. $Note:

When instantiating this function, the user needs to explicitly pass in the scalar type, for example CalcProbabilityDensity<double>(…), the compiler might have problem to deduce the scalar type automatically.

pydrake.common.configure_logging()

Convenience function that configures the root Python logging module in a tasteful way for Drake. Using this function is totally optional; there is no requirement to call it prior to using Drake or generating messages. We offer it as a convenience only because Python’s logging defaults are more spartan than Drake’s C++ logging format (e.g., Python does not show message timestamps by default).

Note

pydrake logs using Python’s built-in logging module. To access pydrake’s logging.Logger, use logging.getLogger("drake"). You can configure log settings using that object whether or not you have called configure_logging() first.

pydrake.common.FindResourceOrThrow(resource_path: str) str

(Advanced) Convenient wrapper for querying FindResource(resource_path) followed by FindResourceResult::get_absolute_path_or_throw().

The primary purpose of this function is for Drake’s software internals to locate Drake resources (e.g., config files) within Drake’s build system. In most cases, end users should not need to use it.

Do NOT use this function to feed into a drake::multibody::parsing::Parser. Instead, use parser.AddModelsFromUrl() in coordination with the parser’s PackageMap.

pydrake.common.GetDrakePath() object

(Advanced) Returns the fully-qualified path to the first folder containing Drake resources as located by FindResource, or nullopt if none is found. For example ${result}/examples/pendulum/Pendulum.urdf would be the path to the Pendulum example’s URDF resource.

Most users should prefer FindResource() or FindResourceOrThrow() to locate Drake resources for a specific resource filename. This method only exists for legacy compatibility reasons, and might eventually be removed.

class pydrake.common.MemoryFile

A virtual file, stored in memory.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.MemoryFile) -> None

Default constructor with no contents, checksum, or filename hint. In this case, the checksum will be the checksum of the empty contents.

  1. __init__(self: pydrake.common.MemoryFile, contents: str, extension: str, filename_hint: str) -> None

Constructs a new file from the given contents.

Parameter contents:

The contents of a file.

Parameter extension:

The extension typically associated with the file contents. The case is unimportant, but it must either be empty or of the form .foo.

Parameter filename_hint:

A label for the file. The label is used for warning and error messages. Otherwise, the label has no other functional purpose. It need not be a valid file name, but must consist of a single line (no newlines).

Warning

An empty extension may be problematic. Many consumers of MemoryFile key on the extension to determine if the file is suitable for a purpose. Always provide an accurate, representative extension when possible.

Raises
  • RuntimeError if filename_hint contains newlines.

  • RuntimeError if extension is not empty and the first character

  • isn't '.'.

contents(self: pydrake.common.MemoryFile) bytes

Returns the file’s contents.

extension(self: pydrake.common.MemoryFile) str

Returns the extension (as passed to the constructor). When not empty, it will always be reported with a leading period and all lower case characters.

filename_hint(self: pydrake.common.MemoryFile) str

Returns the notional “filename” for this file`.

static Make(path: os.PathLike) pydrake.common.MemoryFile

Creates an instance of MemoryFile from the file located at the given path. The filename_hint() will be the stringified path. Making a MemoryFile computes the hash of its contents. If all you want is the contents, use drake::ReadFile() or drake::ReadFileOrThrow() instead.

Raises

RuntimeError if the file at path cannot be read.

sha256(self: pydrake.common.MemoryFile) pydrake.common.Sha256

Returns the checksum of this instance’s contents().

class pydrake.common.Parallelism

Specifies a desired degree of parallelism for a parallelized operation.

This class denotes a specific number of threads; either 1 (no parallelism), a user-specified value (any number >= 1), or the maximum number. For convenience, conversion from bool is provided so that False is no parallelism and True is maximum parallelism.

Drake’s API uses this class to allow users to control the degree of parallelism, regardless of how the parallelization is implemented (e.g., std::async, OpenMP, TBB, etc).

The number of threads denoted by Parallelism::Max() is configurable with environment variables, but will be invariant within a single process. The first time it’s accessed, the configured value will be latched into a global variable indefinitely. To ensure your configuration is obeyed, any changes to the environment variables that govern the max parallelism should be made prior to importing or calling any Drake code.

The following recipe determines the value that Parallelism::Max().num_threads() will report:

1. The default is the hardware limit from std::thread::hardware_concurrency(); this will be used when none of the special cases below are in effect.

2. If the environment variable DRAKE_NUM_THREADS is set to a positive integer less than hardware_concurrency(), the num_threads will be that value.

3. If the environment variable DRAKE_NUM_THREADS is not set but the environment variable OMP_NUM_THREADS is set to a positive integer less than hardware_concurrency(), the num_threads will be that value. (Note in particular that a comma-separated OMP_NUM_THREADS value will be ignored, even though that syntax might be valid for an OpenMP library).

The configuration recipe above does not require Drake to be built with OpenMP enabled. The inspection of OMP_NUM_THREADS as a configuration value is provided for convenience, regardless of whether OpenMP is enabled.

A note for Drake developers

In Drake’s unit tests, DRAKE_NUM_THREADS is set to “1” by default. If your unit test requires actual parallelism, use the num_threads = N attribute in the BUILD.bazel file to declare a different value.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.Parallelism) -> None

Default constructs with no parallelism (i.e., num_threads=1).

  1. __init__(self: pydrake.common.Parallelism, parallelize: bool) -> None

Constructs a Parallelism with either no parallelism (i.e., num_threads=1) or the maximum number of threads (Max()), as selected by parallelize. This constructor allows for implicit conversion, for convenience.

  1. __init__(self: pydrake.common.Parallelism, num_threads: int) -> None

Constructs with the provided number of threads num_threads.

Precondition:

num_threads >= 1.

Note

Constructing and using a Parallelism with num_threads greater than the actual hardware concurrency may result in fewer than the specified number of threads actually being launched or poor performance due to CPU contention.

static Max() pydrake.common.Parallelism

Constructs a Parallelism with the maximum number of threads. Refer to the class overview documentation for how to configure the maximum.

num_threads(self: pydrake.common.Parallelism) int

Returns the degree of parallelism. The result will always be >= 1.

pydrake.common.pretty_class_name(cls: type, *, use_qualname: bool = False) str

Given a class, returns its cls.__name__ respelled to be suitable for display to a user, in particular by respelling C++ template arguments using their conventional FooBar_[AutoDiffXd] expression spelling instead of the mangled unicode name. Note that the returned name might not be a valid Python identifier, though it should still be a valid Python expression.

If the class is not a template, simply returns cls.__name__ unchanged.

When use_qualname is true, uses cls.__qualname__ instead of cls.__name__.

class pydrake.common.RandomDistribution

Drake supports explicit reasoning about a few carefully chosen random distributions.

Members:

kUniform : Vector elements are independent and uniformly distributed

kGaussian : Vector elements are independent and drawn from a

kExponential : Vector elements are independent and drawn from an

__init__(self: pydrake.common.RandomDistribution, value: int) None
kExponential = <RandomDistribution.kExponential: 2>
kGaussian = <RandomDistribution.kGaussian: 1>
kUniform = <RandomDistribution.kUniform: 0>
property name
property value
class pydrake.common.RandomGenerator

Defines Drake’s canonical implementation of the UniformRandomBitGenerator C++ concept (as well as a few conventional extras beyond the concept, e.g., seeds). This uses the 32-bit Mersenne Twister mt19937 by Matsumoto and Nishimura, 1998. For more information, see https://en.cppreference.com/w/cpp/numeric/random/mersenne_twister_engine

Note: For many workflows in drake, we aim to have computations that are fully deterministic given a single random seed. This is accomplished by passing a RandomGenerator object. To generate random numbers in numpy that are deterministic given the C++ random seed (see drake issue #12632 for the discussion), use e.g.

generator = pydrake.common.RandomGenerator()
random_state = numpy.random.RandomState(generator())

my_random_value = random_state.uniform()
...
__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.common.RandomGenerator) -> None

Creates a generator using the default_seed. Actual creation of the generator is deferred until first use so this constructor is fast and does not allocate any heap memory.

  1. __init__(self: pydrake.common.RandomGenerator, seed: int) -> None

Creates a generator using given seed.

class pydrake.common.Sha256

Represents a SHA-256 cryptographic checksum. See also https://en.wikipedia.org/wiki/SHA-2.

This class is not bound in pydrake, because Python programmers should prefer using https://docs.python.org/3/library/hashlib.html instead.

__init__(self: pydrake.common.Sha256) None

Constructs an all-zero checksum. Note that this is NOT the same as the checksum of empty (zero-sized) data.

static Checksum(arg0: str) pydrake.common.Sha256

Computes the checksum of the given data buffer.

static Parse(arg0: str) Optional[pydrake.common.Sha256]

Parses the 64-character ASCII hex representation of a SHA-256 checksum. Returns std::nullopt if the argument is an invalid checksum.

to_string(self: pydrake.common.Sha256) str

Returns the 64-character ASCII hex representation of this checksum.

pydrake.common.temp_directory() str

Returns a directory location suitable for temporary files. The directory will be called ${parent}/robotlocomotion_drake_XXXXXX where each X is replaced by a character from the portable filename character set. The path ${parent} is defined as one of the following (in decreasing priority):

  • ${TEST_TMPDIR} - ${TMPDIR} - /tmp

If successful, this will always create a new directory. While the caller is not obliged to delete the directory, it has full power to do so based on specific context and need.

Returns

The path representing a newly created directory There will be no trailing /.

Raises
  • if the directory ${parent}/robotlocomotion_drake_XXXXXX cannot be

  • created, or is not a directory.

class pydrake.common.ToleranceType

Members:

kAbsolute :

kRelative :

__init__(self: pydrake.common.ToleranceType, value: int) None
kAbsolute = <ToleranceType.kAbsolute: 0>
kRelative = <ToleranceType.kRelative: 1>
property name
property value
pydrake.common.trigger_an_assertion_failure() None

Trigger a Drake C++ assertion failure

pydrake.common.use_native_cpp_logging()

By default, pydrake’s C++ code routes all of its log messages to Python’s logging module; this function opts-out of that feature.

After this function has been called, pydrake’s C++ code will log directly to stderr, with no interaction with Python. (The Python settings for log level threshold and message formatting will no longer affect the C++ log messages.)

This can be useful to avoid C++ logging touching the GIL, e.g., when using Python’s threading module.

This function is not thread-safe. No other threads should be running when it is called.

See also the environment variable DRAKE_PYTHON_LOGGING, which can also be used to opt-out.

Raises

RuntimeError – If the reconfiguration is not possible, e.g., if you have already manually adjusted the C++ logging configuration.