|
| int | get_active_nonlinear_equality_constraints_dimension () const =delete |
| |
| int | get_active_nonlinear_inequality_constraints_dimension () const =delete |
| |
| int | get_joint_velocity_constraint_dimension () const =delete |
| |
| Eigen::MatrixXd | GetBounds () const =delete |
| |
| Eigen::VectorXd | GetEquality () const =delete |
| |
| Eigen::VectorXd | GetEquality (int t) const =delete |
| |
| Eigen::SparseMatrix< double > | GetEqualityJacobian () const =delete |
| |
| Eigen::MatrixXd | GetEqualityJacobian (int t) const =delete |
| |
| std::vector< Eigen::Triplet< double > > | GetEqualityJacobianTriplets () const =delete |
| |
| Eigen::VectorXd | GetGoalEQ (const std::string &task_name, int t=0)=delete |
| |
| Eigen::VectorXd | GetGoalNEQ (const std::string &task_name, int t=0)=delete |
| |
| Eigen::VectorXd | GetInequality () const =delete |
| |
| Eigen::VectorXd | GetInequality (int t) const =delete |
| |
| Eigen::SparseMatrix< double > | GetInequalityJacobian () const =delete |
| |
| Eigen::MatrixXd | GetInequalityJacobian (int t) const =delete |
| |
| std::vector< Eigen::Triplet< double > > | GetInequalityJacobianTriplets () const =delete |
| |
| Eigen::VectorXd | GetJointVelocityConstraint () const =delete |
| |
| Eigen::MatrixXd | GetJointVelocityConstraintBounds () const =delete |
| |
| std::vector< Eigen::Triplet< double > > | GetJointVelocityConstraintJacobianTriplets () const =delete |
| |
| Eigen::VectorXd | GetJointVelocityLimits () const =delete |
| |
| double | GetRhoEQ (const std::string &task_name, int t=0)=delete |
| |
| double | GetRhoNEQ (const std::string &task_name, int t=0)=delete |
| |
| void | Instantiate (const UnconstrainedTimeIndexedProblemInitializer &init) override |
| | Instantiates the problem from an Initializer. More...
|
| |
| bool | IsValid () override |
| | Evaluates whether the problem is valid. More...
|
| |
| void | PreUpdate () override |
| | Updates internal variables before solving, e.g., after setting new values for Rho. More...
|
| |
| void | SetGoalEQ (const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)=delete |
| |
| void | SetGoalNEQ (const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0)=delete |
| |
| void | SetJointVelocityLimits (const Eigen::VectorXd &qdot_max_in)=delete |
| |
| void | SetRhoEQ (const std::string &task_name, const double rho, int t=0)=delete |
| |
| void | SetRhoNEQ (const std::string &task_name, const double rho, int t=0)=delete |
| |
| | UnconstrainedTimeIndexedProblem ()=default |
| |
| virtual void | Update (Eigen::VectorXdRefConst x_in, int t) |
| | Updates an individual timestep from a given state vector. More...
|
| |
| void | Update (Eigen::VectorXdRefConst x_in, int t) override |
| | Updates an individual timestep from a given state vector. More...
|
| |
| void | Update (Eigen::VectorXdRefConst x_trajectory_in) |
| | Updates the entire problem from a given trajectory (e.g., used in an optimization solver) More...
|
| |
| virtual | ~UnconstrainedTimeIndexedProblem ()=default |
| |
| | AbstractTimeIndexedProblem () |
| |
| int | get_active_nonlinear_equality_constraints_dimension () const |
| | Returns the dimension of the active equality constraints. More...
|
| |
| int | get_active_nonlinear_inequality_constraints_dimension () const |
| | Returns the dimension of the active inequality constraints. More...
|
| |
| double | get_ct () const |
| | Returns the cost scaling factor. More...
|
| |
| int | get_joint_velocity_constraint_dimension () const |
| | Returns the dimension of the joint velocity constraint (linear inequality). More...
|
| |
| Eigen::MatrixXd | GetBounds () const |
| | Returns the joint bounds (first column lower, second column upper). More...
|
| |
| double | GetCost () const |
| | Returns the scalar cost for the entire trajectory (both task and transition cost). More...
|
| |
| Eigen::RowVectorXd | GetCostJacobian () const |
| | Returns the Jacobian of the scalar cost over the entire trajectory (Jacobian of GetCost). More...
|
| |
| double | GetDuration () const |
| | Returns the duration of the trajectory (T * tau). More...
|
| |
| Eigen::VectorXd | GetEquality () const |
| | Returns the equality constraint values for the entire trajectory. More...
|
| |
| Eigen::VectorXd | GetEquality (int t) const |
| | Returns the value of the equality constraints at timestep t. More...
|
| |
| Eigen::SparseMatrix< double > | GetEqualityJacobian () const |
| | Returns the sparse Jacobian matrix of the equality constraints over the entire trajectory. More...
|
| |
| Eigen::MatrixXd | GetEqualityJacobian (int t) const |
| | Returns the Jacobian of the equality constraints at timestep t. More...
|
| |
| std::vector< Eigen::Triplet< double > > | GetEqualityJacobianTriplets () const |
| | Returns a vector of triplets to fill a sparse Jacobian for the equality constraints. More...
|
| |
| Eigen::VectorXd | GetGoal (const std::string &task_name, int t=0) |
| | Returns the goal for a given task at a given timestep (cost task). More...
|
| |
| Eigen::VectorXd | GetGoalEQ (const std::string &task_name, int t=0) |
| | Returns the goal for a given task at a given timestep (equality task). More...
|
| |
| Eigen::VectorXd | GetGoalNEQ (const std::string &task_name, int t=0) |
| | Returns the goal for a given task at a given timestep (goal task). More...
|
| |
| Eigen::VectorXd | GetInequality () const |
| | Returns the inequality constraint values for the entire trajectory. More...
|
| |
| Eigen::VectorXd | GetInequality (int t) const |
| | Returns the value of the inequality constraints at timestep t. More...
|
| |
| Eigen::SparseMatrix< double > | GetInequalityJacobian () const |
| | Returns the sparse Jacobian matrix of the inequality constraints over the entire trajectory. More...
|
| |
| Eigen::MatrixXd | GetInequalityJacobian (int t) const |
| | Returns the Jacobian of the inequality constraints at timestep t. More...
|
| |
| std::vector< Eigen::Triplet< double > > | GetInequalityJacobianTriplets () const |
| | Returns a vector of triplets to fill a sparse Jacobian for the inequality constraints. More...
|
| |
| std::vector< Eigen::VectorXd > | GetInitialTrajectory () const |
| | Returns the initial trajectory/seed. More...
|
| |
| Eigen::VectorXd | GetJointVelocityConstraint () const |
| | Returns the joint velocity constraint inequality terms (linear). More...
|
| |
| Eigen::MatrixXd | GetJointVelocityConstraintBounds () const |
| | Returns the joint velocity constraint bounds (constant terms). More...
|
| |
| std::vector< Eigen::Triplet< double > > | GetJointVelocityConstraintJacobianTriplets () const |
| | Returns the joint velocity constraint Jacobian as triplets. More...
|
| |
| Eigen::VectorXd | GetJointVelocityLimits () const |
| | Returns the per-DoF joint velocity limit vector. More...
|
| |
| double | GetRho (const std::string &task_name, int t=0) |
| | Returns the precision (Rho) for a given task at a given timestep (cost task). More...
|
| |
| double | GetRhoEQ (const std::string &task_name, int t=0) |
| | Returns the precision (Rho) for a given task at a given timestep (equality task). More...
|
| |
| double | GetRhoNEQ (const std::string &task_name, int t=0) |
| | Returns the precision (Rho) for a given task at a given timestep (equality task). More...
|
| |
| double | GetScalarTaskCost (int t) const |
| | Returns the scalar task cost at timestep t. More...
|
| |
| Eigen::RowVectorXd | GetScalarTaskJacobian (int t) const |
| | Returns the Jacobian of the scalar task cost at timestep t. More...
|
| |
| double | GetScalarTransitionCost (int t) const |
| | Returns the scalar transition cost (x^T*W*x) at timestep t. More...
|
| |
| Eigen::RowVectorXd | GetScalarTransitionJacobian (int t) const |
| | Returns the Jacobian of the transition cost at timestep t. More...
|
| |
| int | GetT () const |
| | Returns the number of timesteps in the trajectory. More...
|
| |
| double | GetTau () const |
| | Returns the time discretization tau for the trajectory. More...
|
| |
| void | SetGoal (const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0) |
| | Sets goal for a given task at a given timestep (cost task). More...
|
| |
| void | SetGoalEQ (const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0) |
| | Sets goal for a given task at a given timestep (equality task). More...
|
| |
| void | SetGoalNEQ (const std::string &task_name, Eigen::VectorXdRefConst goal, int t=0) |
| | Sets goal for a given task at a given timestep (inequality task). More...
|
| |
| void | SetInitialTrajectory (const std::vector< Eigen::VectorXd > &q_init_in) |
| | Sets the initial trajectory/seed. More...
|
| |
| void | SetJointVelocityLimits (const Eigen::VectorXd &qdot_max_in) |
| | Sets the joint velocity limits. Supports N- and 1-dimensional vectors. More...
|
| |
| void | SetRho (const std::string &task_name, const double rho, int t=0) |
| | Sets Rho for a given task at a given timestep (cost task). More...
|
| |
| void | SetRhoEQ (const std::string &task_name, const double rho, int t=0) |
| | Sets Rho for a given task at a given timestep (equality task). More...
|
| |
| void | SetRhoNEQ (const std::string &task_name, const double rho, int t=0) |
| | Sets Rho for a given task at a given timestep (inequality task). More...
|
| |
| void | SetT (const int T_in) |
| | Sets the number of timesteps in the trajectory. Note: Rho/Goal need to be updated for every timestep after calling this method. More...
|
| |
| void | SetTau (const double tau_in) |
| | Sets the time discretization tau for the trajectory. More...
|
| |
| void | Update (Eigen::VectorXdRefConst x_trajectory_in) |
| | Updates the entire problem from a given trajectory (e.g., used in an optimization solver) More...
|
| |
| virtual | ~AbstractTimeIndexedProblem () |
| |
| virtual Eigen::VectorXd | ApplyStartState (bool update_traj=true) |
| |
| int | get_num_controls () const |
| |
| int | get_num_positions () const |
| | ! Dimension of planning problem. TODO: Update from positions/velocities/controls and make private. More...
|
| |
| int | get_num_velocities () const |
| |
| std::pair< std::vector< double >, std::vector< double > > | GetCostEvolution () const |
| |
| double | GetCostEvolution (int index) const |
| |
| KinematicRequestFlags | GetFlags () const |
| |
| int | GetNumberOfIterations () const |
| |
| unsigned int | GetNumberOfProblemUpdates () const |
| |
| ScenePtr | GetScene () const |
| |
| Eigen::VectorXd | GetStartState () const |
| |
| double | GetStartTime () const |
| |
| TaskMapMap & | GetTaskMaps () |
| |
| TaskMapVec & | GetTasks () |
| |
| void | InstantiateBase (const Initializer &init) override |
| |
| | PlanningProblem () |
| |
| std::string | Print (const std::string &prepend) const override |
| |
| void | ResetCostEvolution (size_t size) |
| |
| void | ResetNumberOfProblemUpdates () |
| |
| void | SetCostEvolution (int index, double value) |
| |
| void | SetStartState (Eigen::VectorXdRefConst x) |
| |
| void | SetStartTime (double t) |
| |
| virtual | ~PlanningProblem () |
| |
| std::string | GetObjectName () |
| |
| void | InstantiateObject (const Initializer &init) |
| |
| | Object () |
| |
| virtual std::string | type () const |
| | Type Information wrapper: must be virtual so that it is polymorphic... More...
|
| |
| virtual | ~Object () |
| |
| virtual std::vector< Initializer > | GetAllTemplates () const =0 |
| |
| | InstantiableBase ()=default |
| |
| virtual | ~InstantiableBase ()=default |
| |
| std::vector< Initializer > | GetAllTemplates () const override |
| |
| Initializer | GetInitializerTemplate () override |
| |
| const UnconstrainedTimeIndexedProblemInitializer & | GetParameters () const |
| |
| void | InstantiateInternal (const Initializer &init) override |
| |