simple_pendulum.trajectory_optimization.direct_collocation
Direct Collocation
Submodules
simple_pendulum.trajectory_optimization.direct_collocation.direct_collocation
Direct Collocation Calculator
- class simple_pendulum.trajectory_optimization.direct_collocation.direct_collocation.DirectCollocationCalculator
Bases:
object
Class to calculate a control trajectory with direct collocation.
- compute_trajectory(N=21, max_dt=0.5, start_state=[0.0, 0.0], goal_state=[3.141592653589793, 0.0], initial_x_trajectory=None)
Compute a trajectory from a start state to a goal state for the pendulum.
- Parameters:
- Nint, default=21
number of collocation points
- max_dtfloat, default=0.5
maximum allowed timestep between collocation points
- start_statearray_like, default=[0.0, 0.0]
the start state of the pendulum [position, velocity]
- goal_statearray_like, default=[np.pi, 0.0]
the goal state for the trajectory
- initial_x_trajectoryarray-like, default=None
initial guess for the state space trajectory ignored if None
- Returns:
- x_trajectorypydrake.trajectories.PiecewisePolynomial
trajectory in state space
- dircolpydrake.systems.trajectory_optimization.DirectCollocation
DirectCollocation pydrake object
- resultpydrake.solvers.mathematicalprogram.MathematicalProgramResult
MathematicalProgramResult pydrake object
- extract_trajectory(x_trajectory, dircol, result, N=801)
Extract time, position, velocity and control trajectories from the outputs of the compute_trajectory function.
- Parameters:
- x_trajectorypydrake.trajectories.PiecewisePolynomial
trajectory in state space
- dircolpydrake.systems.trajectory_optimization.DirectCollocation
DirectCollocation pydrake object
- resultpydrake.solvers.mathematicalprogram.MathematicalProgramResult
MathematicalProgramResult pydrake object
- Nint, default=801
The number of sampling points of the returned trajectories
- Returns:
- time_trajarray_like
the time trajectory
- thetaarray_like
the position trajectory
- theta_dotarray_like
the velocity trajectory
- torque_trajarray_like
the control (torque) trajectory
- init_pendulum(mass=0.57288, length=0.5, damping=0.15, gravity=9.81, torque_limit=2.0)
Initialize the pendulum parameters.
- Parameters:
- massfloat, default=0.57288
mass of the pendulum [kg]
- lengthfloat, default=0.5
length of the pendulum [m]
- dampingfloat, default=0.15
damping factor of the pendulum [kg m/s]
- gravityfloat, default=9.81
gravity (positive direction points down) [m/s^2]
- torque_limitfloat, default=2.0
the torque_limit of the pendulum actuator
- plot_phase_space_trajectory(x_trajectory, save_to=None)
Plot the computed trajectory in phase space.
- Parameters:
- x_trajectorypydrake.trajectories.PiecewisePolynomial
the trajectory returned from the compute_trajectory function.
- save_tostring, default=None
string pointing to the location where the figure is supposed to be stored. If save_to==None, the figure is not stored but shown in a window instead.