Drake
drake::systems::trajectory_optimization Namespace Reference

Classes

class  DirectCollocation
 DirectCollocation implements the approach to trajectory optimization as described in C. More...
 
class  DirectCollocationConstraint
 Implements the direct collocation constraints for a first-order hold on the input and a cubic polynomial representation of the state trajectories. More...
 
class  DirectTranscription
 DirectTranscription is perhaps the simplest implementation of a multiple shooting method, where we have decision variables representing the control and input at every sample time in the trajectory, and one-step of numerical integration provides the dynamic constraints between those decision variables. More...
 
class  GeneralizedConstraintForceEvaluator
 This evaluator computes the generalized constraint force Jᵀλ ∈ ℝ ᴺᵛ, where Nᵥ is the size of the generalized velocities. More...
 
class  JointLimitConstraintForceEvaluator
 Evaluates the joint limit constraint force. More...
 
class  MultipleShooting
 MultipleShooting is an abstract class for trajectory optimization that creates decision variables for inputs, states, and (optionally) sample times along the trajectory, then provides a number of methods for working with those decision variables. More...
 
class  PositionConstraintForceEvaluator
 Evaluates the generalized constraint force from RigidBodyTree::positionConstraint. More...
 

Functions

std::unique_ptr< RigidBodyTree< double > > ConstructFourBarTree ()
 Construct a RigidBodyTree containing a four bar linkage. More...
 
Binding< ConstraintAddDirectCollocationConstraint (std::shared_ptr< DirectCollocationConstraint > constraint, const Eigen::Ref< const VectorXDecisionVariable > &timestep, const Eigen::Ref< const VectorXDecisionVariable > &state, const Eigen::Ref< const VectorXDecisionVariable > &next_state, const Eigen::Ref< const VectorXDecisionVariable > &input, const Eigen::Ref< const VectorXDecisionVariable > &next_input, MathematicalProgram *prog)
 
solvers::Binding< solvers::ConstraintAddDirectCollocationConstraint (std::shared_ptr< DirectCollocationConstraint > constraint, const Eigen::Ref< const solvers::VectorXDecisionVariable > &timestep, const Eigen::Ref< const solvers::VectorXDecisionVariable > &state, const Eigen::Ref< const solvers::VectorXDecisionVariable > &next_state, const Eigen::Ref< const solvers::VectorXDecisionVariable > &input, const Eigen::Ref< const solvers::VectorXDecisionVariable > &next_input, solvers::MathematicalProgram *prog)
 Helper method to add a DirectCollocationConstraint to the prog, ensuring that the order of variables in the binding matches the order expected by the constraint. More...
 

Function Documentation

◆ AddDirectCollocationConstraint() [1/2]

Binding<Constraint> drake::systems::trajectory_optimization::AddDirectCollocationConstraint ( std::shared_ptr< DirectCollocationConstraint constraint,
const Eigen::Ref< const VectorXDecisionVariable > &  timestep,
const Eigen::Ref< const VectorXDecisionVariable > &  state,
const Eigen::Ref< const VectorXDecisionVariable > &  next_state,
const Eigen::Ref< const VectorXDecisionVariable > &  input,
const Eigen::Ref< const VectorXDecisionVariable > &  next_input,
MathematicalProgram prog 
)

◆ AddDirectCollocationConstraint() [2/2]

solvers::Binding<solvers::Constraint> drake::systems::trajectory_optimization::AddDirectCollocationConstraint ( std::shared_ptr< DirectCollocationConstraint constraint,
const Eigen::Ref< const solvers::VectorXDecisionVariable > &  timestep,
const Eigen::Ref< const solvers::VectorXDecisionVariable > &  state,
const Eigen::Ref< const solvers::VectorXDecisionVariable > &  next_state,
const Eigen::Ref< const solvers::VectorXDecisionVariable > &  input,
const Eigen::Ref< const solvers::VectorXDecisionVariable > &  next_input,
solvers::MathematicalProgram prog 
)

Helper method to add a DirectCollocationConstraint to the prog, ensuring that the order of variables in the binding matches the order expected by the constraint.

◆ ConstructFourBarTree()

std::unique_ptr< RigidBodyTree< double > > ConstructFourBarTree ( )

Construct a RigidBodyTree containing a four bar linkage.