Drake
Drake C++ Documentation
drake::planning::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  GcsTrajectoryOptimization
 GcsTrajectoryOptimization implements a simplified motion planning optimization problem introduced in the paper "Motion Planning around Obstacles with Convex Optimization" by Tobia Marcucci, Mark Petersen, David von Wrangel, Russ Tedrake. More...
 
class  KinematicTrajectoryOptimization
 Optimizes a trajectory, q(t) subject to costs and constraints on the trajectory and its derivatives. More...
 
class  MidPointIntegrationConstraint
 Implements the midpoint integration. 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...
 
struct  TimeStep
 

Functions

solvers::Binding< solvers::ConstraintAddDirectCollocationConstraint (std::shared_ptr< DirectCollocationConstraint > constraint, const Eigen::Ref< const solvers::VectorXDecisionVariable > &time_step, 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...
 
std::vector< intGetContinuousRevoluteJointIndices (const multibody::MultibodyPlant< double > &plant)
 Returns a list of indices in the plant's generalized positions which correspond to a continuous revolute joint (a revolute joint with no joint limits). More...
 

Function Documentation

◆ AddDirectCollocationConstraint()

solvers::Binding<solvers::Constraint> drake::planning::trajectory_optimization::AddDirectCollocationConstraint ( std::shared_ptr< DirectCollocationConstraint constraint,
const Eigen::Ref< const solvers::VectorXDecisionVariable > &  time_step,
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.

◆ GetContinuousRevoluteJointIndices()

std::vector<int> drake::planning::trajectory_optimization::GetContinuousRevoluteJointIndices ( const multibody::MultibodyPlant< double > &  plant)

Returns a list of indices in the plant's generalized positions which correspond to a continuous revolute joint (a revolute joint with no joint limits).

This includes the revolute component of PlanarJoint and RpyFloatingJoint.