OpenRAVE Documentation

kinematicreachability Module

6D kinematic reachability space of a robot’s manipulators.

../../_images/kinematicreachability.jpg ../../_images/kinematicreachability_side.jpg

[source]

Running the Generator

openrave.py --database kinematicreachability --robot=robots/barrettsegway.robot.xml

Showing the Reachability (uses mayavi2)

openrave.py --database kinematicreachability --robot=robots/barrettsegway.robot.xml --show

Description

This is the reachability when counting the total number of configurations possible at each pose.

Command-line

Usage: openrave.py --database kinematicreachability [options]

Computes the reachability region of a robot manipulator and python pickles it
into a file.

Options:
  -h, --help            show this help message and exit
  --maxradius=MAXRADIUS
                        The max radius of the arm to perform the computation
  --xyzdelta=XYZDELTA   The max radius of the arm to perform the computation
                        (default=0.04)
  --quatdelta=QUATDELTA
                        The max radius of the arm to perform the computation
                        (default=0.5)
  --usefreespace        If set, will record the number of IK solutions that
                        exist for every transform rather than just finding
                        one. More useful map, but much slower to produce
  --showscale=SHOWSCALE
                        Scales the reachability by this much in order to show
                        colors better (default=1.0)

  OpenRAVE Environment Options:
    --loadplugin=_LOADPLUGINS
                        List all plugins and the interfaces they provide.
    --collision=_COLLISION
                        Default collision checker to use
    --physics=_PHYSICS  physics engine to use (default=none)
    --viewer=_VIEWER    viewer to use (default=qtcoin)
    --server=_SERVER    server to use (default=None).
    --serverport=_SERVERPORT
                        port to load server on (default=4765).
    --module=_MODULES   module to load, can specify multiple modules. Two
                        arguments are required: "name" "args".
    -l _LEVEL, --level=_LEVEL, --log_level=_LEVEL
                        Debug level, one of
                        (fatal,error,warn,info,debug,verbose,verifyplans)
    --testmode          if set, will run the program in a finite amount of
                        time and spend computation time validating results.
                        Used for testing

  OpenRAVE Database Generator General Options:
    --show              Graphically shows the built model
    --getfilename       If set, will return the final database filename where
                        all data is stored
    --gethas            If set, will exit with 0 if datafile is generated and
                        up to date, otherwise will return a 1. This will
                        require loading the model and checking versions, so
                        might be a little slow.
    --robot=ROBOT       OpenRAVE robot to load
                        (default=robots/barrettsegway.robot.xml)
    --numthreads=NUMTHREADS
                        number of threads to compute the database with
                        (default=1)
    --manipname=MANIPNAME
                        The name of the manipulator on the robot to use

Class Definitions

openravepy.databases.kinematicreachability.RaveFindDatabaseFile((str)arg1, (bool)arg2) → str :

OPENRAVE_API std::string RaveFindDatabaseFile(const std::string & filename, bool bRead = true )

Searches for a filename in the database and returns a full path/URL to it.

Parameters
filename -
the relative filename in the database
bRead -
if true will only return a file if it exists. If false, will return the filename of the first valid database directory.
Return
a non-empty string if a file could be found.
class openravepy.databases.kinematicreachability.ReachabilityModel(robot)[source]

Bases: openravepy.databases.DatabaseGenerator

Computes the robot manipulator’s reachability space (stores it in 6D) and offers several functions to use it effectively in planning.

ComputeNN(translationonly=False)[source]
static CreateOptionParser()[source]
static InitializeFromParser(Model=None, parser=None, *args, **kwargs)[source]
LoadHDF5()[source]
LoadPickle()[source]
class QuaternionKDTree(poses, transmult)[source]

Bases: openravepy.metaclass.AutoReloader

Artificially add more weight to the X,Y,Z translation dimensions

kFRSearch(pose, radiussq, k, eps)[source]

returns distance squared

kFRSearchArray(poses, radiussq, k, eps)[source]

returns distance squared

kSearch(poses, k, eps)[source]

returns distance squared

ReachabilityModel.SaveHDF5()[source]
ReachabilityModel.SavePickle()[source]
ReachabilityModel.UniformlySampleSpace(maxradius, delta)[source]
ReachabilityModel.autogenerateparams(options=None)[source]
ReachabilityModel.clone(envother)[source]
ReachabilityModel.generatepcg(maxradius=None, translationonly=False, xyzdelta=None, quatdelta=None, usefreespace=False)[source]

Generate producer, consumer, and gatherer functions allowing parallelization

ReachabilityModel.getOrderedArmJoints()[source]
ReachabilityModel.getfilename(read=False)[source]
ReachabilityModel.getversion()[source]
ReachabilityModel.has()[source]
ReachabilityModel.load()[source]
ReachabilityModel.save()[source]
ReachabilityModel.show(showrobot=True, contours=[0.01, 0.10000000000000001, 0.20000000000000001, 0.5, 0.80000000000000004, 0.90000000000000002, 0.98999999999999999], opacity=None, figureid=1, xrange=None, options=None)[source]
openravepy.databases.kinematicreachability.poseFromMatrix((object)transform) → object :

Converts a 4x4 matrix to a 7 element quaternion+translation representation.

Parameters:transform – 3x4 or 4x4 affine matrix
openravepy.databases.kinematicreachability.rotationMatrixFromQArray((object)quatarray) → object :

Converts an array of quaternions to a list of 3x3 rotation matrices.

Parameters:quatarray – nx4 array
openravepy.databases.kinematicreachability.run(*args, **kwargs)[source]

Command-line execution of the example. args specifies a list of the arguments to the script.

Questions/Feedback

Having problems with OpenRAVE?