OpTaS  1.0.7
An optimization-based task specification library for trajectory optimization and model predictive control.
Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
optas.builder.OptimizationBuilder Class Reference

OptimizationBuilder allows you to build/specify an optimization problem. More...

Public Member Functions

def __init__ (self, int T, List[RobotModel] robots=[], List[TaskModel] tasks=[], bool derivs_align=False)
 OptimizationBuilder constructor. More...
 
List[str] get_model_names (self)
 Return the names of each model. More...
 
int get_model_index (self, str name)
 Return the index of the model in the list of models. More...
 
Model get_model (self, str name)
 Return the model with given name. More...
 
CasADiArrayType get_model_state (self, str name, int t, int time_deriv=0)
 Get the model state at a given time. More...
 
CasADiArrayType get_model_states (self, str name, int time_deriv=0)
 Get the full state trajectory for a given model. More...
 
CasADiArrayType get_model_parameters (self, str name, int time_deriv=0)
 Get the array of parameters for a given model. More...
 
CasADiArrayType get_model_parameter (self, str name, int t, int time_deriv=0)
 Get the model parameter at a given time. More...
 
CasADiArrayType get_robot_states_and_parameters (self, str name, int time_deriv=0)
 Get the vector of states and parameters for a given model. More...
 
cs.DM is_cost_quadratic (self)
 True DM(1) when cost function is quadratic in the decision variables, False DM(0) otherwise. More...
 
cs.SX add_decision_variables (self, str name, int m=1, int n=1, bool is_discrete=False)
 Add decision variables to the optimization problem. More...
 
cs.SX add_parameter (self, str name, int m=1, int n=1)
 Add a parameter to the optimization problem. More...
 
None add_cost_term (self, str name, cs.SX cost_term)
 Add cost term to the optimization problem. More...
 
None add_geq_inequality_constraint (self, str name, CasADiArrayType lhs, Union[None, CasADiArrayType] rhs=None)
 Add the inequality constraint lhs >= rhs to the optimization problem. More...
 
None add_leq_inequality_constraint (self, str name, CasADiArrayType lhs, Union[None, CasADiArrayType] rhs=None)
 Add the inequality constraint lhs <= rhs to the optimization problem. More...
 
None add_bound_inequality_constraint (self, str name, CasADiArrayType lhs, CasADiArrayType mid, CasADiArrayType rhs)
 Add the inequality constraint lhs <= mid <= rhs to the optimization problem. More...
 
None add_equality_constraint (self, str name, CasADiArrayType lhs, Union[None, CasADiArrayType] rhs=None, reduce_constraint=False)
 Add the equality constraint lhs == rhs to the optimization problem. More...
 
None sphere_collision_avoidance_constraints (self, name, obstacle_names, link_names=None, base_link=None)
 Add collision avoidance constraints, based on spherical representations attached to the robot links and placed in the world. More...
 
None integrate_model_states (self, str name, int time_deriv, CasADiArrayType dt)
 Integrates the model states over time. More...
 
None enforce_model_limits (self, str name, int time_deriv=0, Union[None, CasADiArrayType] lo=None, Union[None, CasADiArrayType] up=None, safe_frac=1.0)
 Enforce model limits. More...
 
None initial_configuration (self, str name, Union[None, CasADiArrayType] init=None, int time_deriv=0)
 Set initial configuration. More...
 
None fix_configuration (self, str name, CasADiArrayType config=None, int time_deriv=0, int t=0)
 Fix configuration. More...
 
Optimization build (self)
 Build the optimization problem. More...
 

Public Attributes

 T
 Number of time steps for the trajectory. More...
 
 derivs_align
 When true, the time derivatives align for each time step. More...
 

Private Member Functions

CasADiArrayType _x (self)
 Return the decision variables as a casadi.SX vector. More...
 
CasADiArrayType _p (self)
 Return the parameters as a casadi.SX vector. More...
 
cs.DM _is_linear_in_x (self, cs.SX y)
 Returns true DM(1) if y is a linear function of the decision variables, false DM(0) otherwise. More...
 
CasADiArrayType _cost (self)
 Returns the cost function. More...
 

Private Attributes

 _models
 List of models. More...
 
 _decision_variables
 SXContainer containing decision variables. More...
 
 _parameters
 SXContainer containing parameters. More...
 
 _cost_terms
 SXContainer containing the cost terms. More...
 
 _lin_eq_constraints
 SXContainer containing the linear equality constraints. More...
 
 _lin_ineq_constraints
 SXContainer containing the linear inequality constraints. More...
 
 _ineq_constraints
 SXContainer containing the inequality constraints. More...
 
 _eq_constraints
 SXContainer containing the equality constraints. More...
 

Detailed Description

OptimizationBuilder allows you to build/specify an optimization problem.

Constructor & Destructor Documentation

◆ __init__()

def optas.builder.OptimizationBuilder.__init__ (   self,
int  T,
List[RobotModel]   robots = [],
List[TaskModel]   tasks = [],
bool   derivs_align = False 
)

OptimizationBuilder constructor.

   @param T Number of time steps for the trajectory.
   @param robots A list of robot models.
   @param tasks A list of task models.
   @param derivs_align When true, the time derivatives align for each time step. Default is False.
   @return An instance of the OptimizationBuilder class.

Member Function Documentation

◆ _cost()

CasADiArrayType optas.builder.OptimizationBuilder._cost (   self)
private

Returns the cost function.

   @return The symbolic cost function.

◆ _is_linear_in_x()

cs.DM optas.builder.OptimizationBuilder._is_linear_in_x (   self,
cs.SX  y 
)
private

Returns true DM(1) if y is a linear function of the decision variables, false DM(0) otherwise.

   @param y Symbolic function of interest.
   @return True if y is linear in x.

◆ _p()

CasADiArrayType optas.builder.OptimizationBuilder._p (   self)
private

Return the parameters as a casadi.SX vector.

   @return Symbolic parameters.

◆ _x()

CasADiArrayType optas.builder.OptimizationBuilder._x (   self)
private

Return the decision variables as a casadi.SX vector.

   @return Symbolic decision variables.

◆ add_bound_inequality_constraint()

None optas.builder.OptimizationBuilder.add_bound_inequality_constraint (   self,
str  name,
CasADiArrayType  lhs,
CasADiArrayType  mid,
CasADiArrayType  rhs 
)

Add the inequality constraint lhs <= mid <= rhs to the optimization problem.

   @param name Name for the constraint.
   @param lhs Left-hand side for the inequality constraint.
   @param mid Middle part of the inequality constraint.
   @param rhs Right-hand side for the inequality constraint.

◆ add_cost_term()

None optas.builder.OptimizationBuilder.add_cost_term (   self,
str  name,
cs.SX  cost_term 
)

Add cost term to the optimization problem.

   @param name Name for cost function.
   @param cost_term Cost term, must be an array with shape 1-by-1.

◆ add_decision_variables()

cs.SX optas.builder.OptimizationBuilder.add_decision_variables (   self,
str  name,
int   m = 1,
int   n = 1,
bool   is_discrete = False 
)

Add decision variables to the optimization problem.

   @param name Name of decision variable array.
   @param m Number of rows in decision variable array. Default is 1.
   @param n Number of columns in decision variable array. Default is 1.
   @param is_discret If true, then the decision variables are treated as discrete variables. Default is False.
   @return Array of the decision variables.

◆ add_equality_constraint()

None optas.builder.OptimizationBuilder.add_equality_constraint (   self,
str  name,
CasADiArrayType  lhs,
Union[None, CasADiArrayType]   rhs = None,
  reduce_constraint = False 
)

Add the equality constraint lhs == rhs to the optimization problem.

   @param name Name for the constraint.
   @param lhs Left-hand side for the inequality constraint.
   @param rhs Right-hand side for the inequality constraint. If None, then it is replaced with the zero array with the same shape as lhs.
   @param reduce_constraint When True, the constraints are specified by ||lhs - rhs||^2 = 0. This has the effect of reducing the number of equality constraints in the problem. However, if the constraints are linear they will be treated as nonlinear. Default is False.

◆ add_geq_inequality_constraint()

None optas.builder.OptimizationBuilder.add_geq_inequality_constraint (   self,
str  name,
CasADiArrayType  lhs,
Union[None, CasADiArrayType]   rhs = None 
)

Add the inequality constraint lhs >= rhs to the optimization problem.

   @param name Name for the constraint.
   @param lhs Left-hand side for the inequality constraint.
   @param rhs Right-hand side for the inequality constraint. If None, then it is replaced with the zero array with the same shape as lhs.

◆ add_leq_inequality_constraint()

None optas.builder.OptimizationBuilder.add_leq_inequality_constraint (   self,
str  name,
CasADiArrayType  lhs,
Union[None, CasADiArrayType]   rhs = None 
)

Add the inequality constraint lhs <= rhs to the optimization problem.

   @param name Name for the constraint.
   @param lhs Left-hand side for the inequality constraint.
   @param rhs Right-hand side for the inequality constraint. If None, then it is replaced with the zero array with the same shape as lhs.

◆ add_parameter()

cs.SX optas.builder.OptimizationBuilder.add_parameter (   self,
str  name,
int   m = 1,
int   n = 1 
)

Add a parameter to the optimization problem.

   @param name Name of parameter array.
   @param m Number of rows in parameter array. Default is 1.
   @param n Number of columns in parameter array. Default is 1.
   @return Array of the parameters.

◆ build()

Optimization optas.builder.OptimizationBuilder.build (   self)

Build the optimization problem.

◆ enforce_model_limits()

None optas.builder.OptimizationBuilder.enforce_model_limits (   self,
str  name,
int   time_deriv = 0,
Union[None, CasADiArrayType]   lo = None,
Union[None, CasADiArrayType]   up = None,
  safe_frac = 1.0 
)

Enforce model limits.

   @param name Name of model.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.).
   @param lo Lower limits, if None then model limits specified in the model class are used.
   @param up Upper limits, if None then model limits specified in the model class are used.
   @param safe_frac When safe_frac < 1.0, the joint limits are reduced by a fraction of their original values.

◆ fix_configuration()

None optas.builder.OptimizationBuilder.fix_configuration (   self,
str  name,
CasADiArrayType   config = None,
int   time_deriv = 0,
int   t = 0 
)

Fix configuration.

   @param name Name of model.
   @param config The configuration. When None is passed then it is considered to be zero.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.).
   @param t Index for the configuration in trajectory (by default this is the first element but it could also be the last for example in moving horizon estimation).

◆ get_model()

Model optas.builder.OptimizationBuilder.get_model (   self,
str  name 
)

Return the model with given name.

   @param name Name of the model.
   @return A task or robot model.

◆ get_model_index()

int optas.builder.OptimizationBuilder.get_model_index (   self,
str  name 
)

Return the index of the model in the list of models.

   @param name Name of the model.
   @return Index of the model in the list of models.

◆ get_model_names()

List[str] optas.builder.OptimizationBuilder.get_model_names (   self)

Return the names of each model.

   @return List of model names.

◆ get_model_parameter()

CasADiArrayType optas.builder.OptimizationBuilder.get_model_parameter (   self,
str  name,
int  t,
int   time_deriv = 0 
)

Get the model parameter at a given time.

   @param name Name of the model.
   @param t Index of the desired state.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.).
   @return The parameter vector where dim is the model number of parameters

◆ get_model_parameters()

CasADiArrayType optas.builder.OptimizationBuilder.get_model_parameters (   self,
str  name,
int   time_deriv = 0 
)

Get the array of parameters for a given model.

   @param name Name of the model.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.).
   @return The array of parameters where dim is the number of model parameters, and T is the number of time-steps in the trajectory.

◆ get_model_state()

CasADiArrayType optas.builder.OptimizationBuilder.get_model_state (   self,
str  name,
int  t,
int   time_deriv = 0 
)

Get the model state at a given time.

   @param name Name of the model.
   @param t Index of the desired state.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.)
   @return The state vector where dim is the model dimension.

◆ get_model_states()

CasADiArrayType optas.builder.OptimizationBuilder.get_model_states (   self,
str  name,
int   time_deriv = 0 
)

Get the full state trajectory for a given model.

   @param name Name of the model.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.).
   @return The state vector where dim is the model dimension, and T is the number of time-steps in the trajectory.

◆ get_robot_states_and_parameters()

CasADiArrayType optas.builder.OptimizationBuilder.get_robot_states_and_parameters (   self,
str  name,
int   time_deriv = 0 
)

Get the vector of states and parameters for a given model.

   Note that method only applies to to RobotModel.
   To be replaced by get_model_states_and_parameters once parameters are added to base class Model.

   @param name Name of the model.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.)
   @return The vector of parameters where dim is the number of model states and parameters (for a robot it should correspond to the degrees of freedom), and T is the number of time-steps in the trajectory.

◆ initial_configuration()

None optas.builder.OptimizationBuilder.initial_configuration (   self,
str  name,
Union[None, CasADiArrayType]   init = None,
int   time_deriv = 0 
)

Set initial configuration.

   @param name Name of model.
   @param init Initial configuration. If None is passed then this is assumed to be zero.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.). The default is 0.

◆ integrate_model_states()

None optas.builder.OptimizationBuilder.integrate_model_states (   self,
str  name,
int  time_deriv,
CasADiArrayType   dt 
)

Integrates the model states over time.

   @param name Name of the model.
   @param time_deriv The time-deriviative required (i.e. position is 0, velocity is 1, etc.).
   @param dt Integration time step. If the value is a scalar then the value is used as the time step for the trajectory. When an array is passed, it should have the correct length: ```n = T - (1 if derivs_align else time_deriv)``` where T and derivs_align are flags passed to the optimization builder constructor.

◆ is_cost_quadratic()

cs.DM optas.builder.OptimizationBuilder.is_cost_quadratic (   self)

True DM(1) when cost function is quadratic in the decision variables, False DM(0) otherwise.

   @return Truth value if the cost function is quadratic or not.

◆ sphere_collision_avoidance_constraints()

None optas.builder.OptimizationBuilder.sphere_collision_avoidance_constraints (   self,
  name,
  obstacle_names,
  link_names = None,
  base_link = None 
)

Add collision avoidance constraints, based on spherical representations attached to the robot links and placed in the world.

   @param name Name of the model.
   @param obstacle_names A list of strings with names of obstacles. For each object, parameters will be created with labels NAME_position (size 3) and NAME_radii (size 1) that represent the obstacle position and radius respectively.
   @param link_names The links you want to attach collision avoidance constraints onto; for each link a parameter is created with label NAME_radii (size 1). When None is passed, a sphere is attcahed to each link specified in the URDF.
   @param base_link Name of the base frame link. When None is passed, the root link in the URDF is used.

Member Data Documentation

◆ _cost_terms

optas.builder.OptimizationBuilder._cost_terms
private

SXContainer containing the cost terms.

◆ _decision_variables

optas.builder.OptimizationBuilder._decision_variables
private

SXContainer containing decision variables.

◆ _eq_constraints

optas.builder.OptimizationBuilder._eq_constraints
private

SXContainer containing the equality constraints.

◆ _ineq_constraints

optas.builder.OptimizationBuilder._ineq_constraints
private

SXContainer containing the inequality constraints.

◆ _lin_eq_constraints

optas.builder.OptimizationBuilder._lin_eq_constraints
private

SXContainer containing the linear equality constraints.

◆ _lin_ineq_constraints

optas.builder.OptimizationBuilder._lin_ineq_constraints
private

SXContainer containing the linear inequality constraints.

◆ _models

optas.builder.OptimizationBuilder._models
private

List of models.

◆ _parameters

optas.builder.OptimizationBuilder._parameters
private

SXContainer containing parameters.

◆ derivs_align

optas.builder.OptimizationBuilder.derivs_align

When true, the time derivatives align for each time step.

◆ T

optas.builder.OptimizationBuilder.T

Number of time steps for the trajectory.


The documentation for this class was generated from the following file: