6D kinematic reachability space of a robot’s manipulators.
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
This is the reachability when counting the total number of configurations possible at each pose.
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
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.
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.
Bases: openravepy.metaclass.AutoReloader
Artificially add more weight to the X,Y,Z translation dimensions
Converts a 4x4 matrix to a 7 element quaternion+translation representation.
Parameters: | transform – 3x4 or 4x4 affine matrix |
---|
Converts an array of quaternions to a list of 3x3 rotation matrices.
Parameters: | quatarray – nx4 array |
---|