| Home | Trees | Indices | Help |
|
|---|
|
|
逆運動学解析解の自動作成
Running the Generator
openrave.py --database inversekinematics --robot=robots/barrettsegway.robot.xml
Testing the Solvers
openrave.py --database inversekinematics --robot=robots/barrettsegway.robot.xml --iktests=100
Dynamically generate/load the inverse kinematics for a robot's manipulator:
robot.SetActiveManipulator(...)
ikmodel = openravepy.databases.inversekinematics.InverseKinematicsModel(robot,iktype=IkParameterization.Type.Transform6D)
if not ikmodel.load():
ikmodel.autogenerate()
This process allows users to generate OpenRAVE inverse kinematics solvers for any robot manipulator. The manipulator's arm joints are used for obtaining the joints to solve for. The user can specify the IK type (Rotation, Translation, Full 6D, Ray 4D, etc), the free joints of the kinematics, and the accuracy. For example, generating the right arm 6D IK for the PR2 robot where the free joint is the first joint and the free increment is 0.01 radians is:
openrave.py --database inversekinematics --robot=robots/pr2-beta-static.robot.xml --manipname=rightarm --freejoint=r_shoulder_pan_joint --freeinc=0.01
Generating the 3d rotation IK for the stage below is:
openrave.py --database inversekinematics --robot=robots/rotation_stage.robot.xml --rotation3donly
Generating the ray inverse kinematics for the 4 degrees of freedom barrett wam is:
openrave.py --database inversekinematics --robot=drill.robot.xml --ray4donly
Every IK solver should be tested with the robot using --iktests=XXX. However, calling inversekinematics will always re-generate the IK, even if one already exists. In order to just run tests, it is possible to specify the --usecached option to prevent re-generation and specifically test:
openrave.py --database inversekinematics --robot=robots/barrettwam.robot.xml --usecached --iktests=100
This will give the success rate along with information whether the IK gives a wrong results or fails to find a solution.
If there are a lot of free joints in the IK solver, then their discretization can greatly affect whether solutions are found or not. In this case, it is advisable to reduce the discretization threshold by using the --freeinc option.
It is possible to use the auto-generation process through c++ by loading the IKFast problem and calling LoadIKFastSolver command. Check out the ikfastloader.cpp example program.
Author: Rosen Diankov
Copyright: Copyright (C) 2009-2010 Rosen Diankov (rosen.diankov@gmail.com)
License: Apache License, Version 2.0
| Classes | |
|
InverseKinematicsModel Generates analytical inverse-kinematics solutions, compiles them into a shared object/DLL, and sets the robot's iksolver. Only generates the models for the robot's active manipulator. To generate IK models for each manipulator in the robot, mulitple InverseKinematicsModel classes have to be created. |
|
| Functions | |||
|
|||
| Variables | |
__package__ =
|
|
| Function Details |
Executes the inversekinematics database generation, args specifies a list of the arguments to the script. Help
Usage: openrave.py --database inversekinematics [options]
Computes the closed-form inverse kinematics equations of a robot manipulator,
generates a C++ file, and compiles this file into a shared object which can
then be loaded by OpenRAVE
Options:
-h, --help show this help message and exit
--freejoint=FREEJOINTS
Optional joint name specifying a free parameter of the
manipulator. If nothing specified, assumes all joints
not solving for are free parameters. Can be specified
multiple times for multiple free parameters.
--precision=PRECISION
The precision to compute the inverse kinematics in,
(default=10).
--accuracy=ACCURACY The small number that will be recognized as a zero
used to eliminate floating point errors
(default=1e-07).
--usecached If set, will always try to use the cached ik c++ file,
instead of generating a new one.
--rotation3donly [deprecated] If true, need to specify only 3 solve
joints and will solve for a target rotation
--direction3donly [deprecated] If true, need to specify only 2 solve
joints and will solve for a target direction
--translation3donly [deprecated] If true, need to specify only 3 solve
joints and will solve for a target translation
--ray4donly [deprecated] If true, need to specify only 4 solve
joints and will solve for a target ray
--usedummyjoints Treat the unspecified joints in the kinematic chain as
dummy and set them to 0. If not specified, treats all
unspecified joints as free parameters.
--freeinc=FREEINC The discretization value of freejoints.
--numiktests=IKTESTS, --iktests=IKTESTS
Will test the ik solver and return the success rate.
IKTESTS can be an integer to specify number of random
tests, it can also be a filename to specify the joint
values of the manipulator to test. The formst of the
filename is #numiktests [dof values]*
--perftiming=PERFTIMING
Number of IK calls for measuring the internal ikfast
solver.
--outputlang=OUTPUTLANG
If specified, will output the generated code in that
language (ie --outputlang=cpp).
--iktype=IKTYPE The ik type to build the solver current types are:
Transform6D, Rotation3D, Translation3D, Direction3D,
Ray4D
OpenRAVE Environment Options:
--collision=COLLISION
Default collision checker to use
--physics=PHYSICS Default physics engine to use
-d DEBUG, --debug=DEBUG
Debug level
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)
--manipname=MANIPNAME
The name of the manipulator on the robot to use
|
| Home | Trees | Indices | Help |
|
|---|
| Generated by Epydoc 3.0.1 on Wed Aug 11 10:41:00 2010 | http://epydoc.sourceforge.net |