simple_pendulum.controllers.energy_shaping
Energy Shaping Control
Submodules
simple_pendulum.controllers.energy_shaping.energy_shaping_controller
Energy Shaping Controller
- class simple_pendulum.controllers.energy_shaping.energy_shaping_controller.EnergyShapingAndLQRController(mass=1.0, length=0.5, damping=0.1, coulomb_fric=0.0, gravity=9.81, torque_limit=inf, k=1.0, Q=array([[10, 0], [0, 1]]), R=array([[1]]), compute_RoA=False)
Bases:
AbstractController
Controller which swings up the pendulum with the energy shaping controller and stabilizes the pendulum with the lqr controller.
- get_control_output(meas_pos, meas_vel, meas_tau=0, meas_time=0, verbose=False)
The function to compute the control input for the pendulum actuator
- Parameters:
- meas_posfloat
the position of the pendulum [rad]
- meas_velfloat
the velocity of the pendulum [rad/s]
- meas_taufloat
the meastured torque of the pendulum [Nm] (not used)
- meas_timefloat
the collapsed time [s] (not used)
- verbosebool, default=False
whether to print when the controller switches between energy shaping and lqr
- Returns:
- des_posfloat
the desired position of the pendulum [rad] (not used, returns None)
- des_velfloat
the desired velocity of the pendulum [rad/s] (not used, returns None)
- des_taufloat
the torque supposed to be applied by the actuator [Nm]
- get_swingup_time()
- set_goal(x)
Set the goal for the controller.
- Parameters:
- xarray-like
the goal state for the pendulum
- class simple_pendulum.controllers.energy_shaping.energy_shaping_controller.EnergyShapingController(mass=1.0, length=0.5, damping=0.1, gravity=9.81, torque_limit=2.0, k=1.0)
Bases:
AbstractController
Controller which swings up the pendulum by regulating its energy.
- get_control_output(meas_pos, meas_vel, meas_tau=0, meas_time=0)
The function to compute the control input for the pendulum actuator
- Parameters:
- meas_posfloat
the position of the pendulum [rad]
- meas_velfloat
the velocity of the pendulum [rad/s]
- meas_taufloat
the meastured torque of the pendulum [Nm] (not used)
- meas_timefloat
the collapsed time [s] (not used)
- Returns:
- des_posfloat
the desired position of the pendulum [rad] (not used, returns None)
- des_velfloat
the desired velocity of the pendulum [rad/s] (not used, returns None)
- des_taufloat
the torque supposed to be applied by the actuator [Nm]
- set_goal(x)
Set the goal for the controller. This function calculates the energy of the goal state.
- Parameters:
- xarray-like
the goal state for the pendulum