klampt.plan.robotoptimize module
- class klampt.plan.robotoptimize.KlamptVariable(name, type)[source]
Bases:
object
- name
the Klamp’t item’s name
- Type:
str
- type
the Klamp’t item’s type
- Type:
str
- encoding
the way in which the item is encoded in the optimization
- Type:
str
- expr
the Expression that will be used to replace the symbolic mainVariable via appropriate variables
- Type:
- constraints, encoder, decoder
internally used
- class klampt.plan.robotoptimize.RobotOptimizationProblem(robot=None, world=None, *ikgoals)[source]
Bases:
OptimizationProblemBuilder
Defines a generalized optimization problem for a robot, which is a subclass of OptimizationProblemBuilder. This may easily incorporate IK constraints, and may have additional specifications of active DOF.
- robot
- Type:
- world
the world containing possible obstacles
- Type:
WorldModel, optional
- context
a symbolic.KlamptContext that stores the variable q denoting the robot configuration, as well as any user data. User data “robot” and “world” are available by default.
- Type:
KlamptContext, inherited
- activeDofs
the list of active robot DOFs.
- Type:
list
- autoLoad
a dictionary of (userDataName:fileName) pairs that are stored so that user data is automatically loaded from files. I.e., upon self.loadJson(), for each pair in autoLoad the command self.context.userData[userDataName] = loader.load(fileName) is executed.
- Type:
dict
- managedVariables
a dictionary of KlamptVariables like rotations and rigid transforms.
Managed variables should be referred to in parsed expressions with the prefix @name, and are encoded into optimization form and decoded from optimization form using KlamptVariable.bind / KlamptVariable.unbind. You can also retrieve the Klampt value by KlamptVariable.getValue().
- Type:
dict of KlamptVariable
If you would like to find the configuration closest to solving the IK constraints, either add the IK constraints one by one with weight=1 (or some other numeric value), or call enableSoftIK() after the constraints have been added. In this case, solve will always return a solution, as long as it finds a configuration that passes the feasibility tests. The optimization method changes so that it 1) optimizes the residual norm, and then 2) optimizes the cost function to maintain the residual norm at its current value. In other words, minimizing error is the first priority and minimizing cost is the second priority.
- enableSoftIK(enabled=True)[source]
Turns on soft IK solving. This is the same as hard IK solving if all constraints can be reached, but if the constraints cannot be reached, it will try to optimize the error.
- addIKObjective(obj, weight=None)[source]
Adds a new IKObjective to the problem. If weight is not None, it is added as a soft constraint.
- addUserData(name, fn)[source]
Adds an auto-loaded userData. Raises an exception if fn cannot be loaded.
Arguments: - name: the name of the userData. - fn: the file from which it is loaded. It must be loadable with loader.load.
- addKlamptVar(name, type=None, initialValue=None, encoding='auto', constraints=True, optimize=True)[source]
Adds one or more variables of a given Klamp’t type (e.g., “Config”, “Rotation”, “RigidTransform”). If necessary, constraints on the object will also be added, e.g., joint limits, or a quaternion unit norm constraint.
At least one of type / initialValue must be provided.
- Parameters:
name (str) – a name for the variable.
type (str, optional) – a supported variable type (default None determines the type by initialValue). Supported types include “Config”, “Configs”, Rotation”, “RigidTransform”, “Vector3”. Future work may support Trajectory and other types.
initialValue (optional) – the configuration of the variable. If it’s a float, the type will be set to numeric, if it’s a list it will be set to a vector, or if its a supported object, the type will be set appropriately and config.getConfig(initialValue) will be used for its parameter setting.
encoding (str, optional) –
only supported for Rotation and RigidTransform types, and defines how the variable will be parameterized in optimization. Can be:
’rotation_vector’ (default) for rotation vector, 3 parameters
’quaternion’ for quaternion encoding, 4 parameters + 1 constraint
’rpy’ for roll-pitch-yaw euler angles, 3 parameters
None for full rotation matrix (9 parameters, 6 constraints)
’auto’ (equivalent to to ‘rotation_vector’)
constraints (bool, optional) – True if all default constraints are to be added. For Config / Configs types, bound constraints at the robot’s joint limits are added.
optimize (bool, optional) – If True, adds the parameterized variables to the list of optimization variables.
- Returns:
- an object containing information about the encoding of the variable.
Note that extra symbolic Variable names may be decorated with extensions in the form of “_ext” if the encoding is not direct.
- Return type:
- get(name, defaultValue=None)[source]
Returns a Variable or UserData in the context, or a managed KlamptVariable. If the item does not exist, defaultValue is returned.
- setActiveDofs(links)[source]
Sets the list of active DOFs. These may be indices, RobotModelLinks, or strings.
- enableDof(link)[source]
Enables an active DOF. If this is the first time enableDof is called, this initializes the list of active DOFs to the single link. Otherwise it appends it to the list. (By default, all DOFs are enabled)
- setJointLimits(qmin=None, qmax=None)[source]
Sets the joint limits to the given lists qmin,qmax. By default, the robot’s joint limits are used.
- toJson(saveContextFunctions=False, prettyPrintExprs=False)[source]
Returns a JSON object representing this optimization problem.
- Parameters:
saveContextFunctions (bool, optional) – if True, saves all custom functions in self.context. If they are saved, then the current context is required to be the same context in which the problem is loaded.
prettyPrintExprs (bool, optional) – if True, prints expressions more nicely as more human-readable strings rather than JSON objects. These strings are parsed on load, which is a little slower than pure JSON.
- fromJson(obj, doAutoLoad=True)[source]
Loads from a JSON-compatible object.
- Parameters:
obj – the JSON-compatible object
doAutoLoad (bool, optional) – if True, performs the auto-loading step. An IOError is raised if any item can’t be loaded.
- solve(params=<klampt.math.optimize.OptimizerParams object>)[source]
Locally or globally solves the given problem (using the robot’s current configuration as a seed if params.startRandom=False). Returns the solution configuration or None if failed.
- Parameters:
params (OptimizerParams, optional) – configures the optimizer.