simple_pendulum.controllers
Controllers
Subpackages
- simple_pendulum.controllers.ddpg
- simple_pendulum.controllers.energy_shaping
- simple_pendulum.controllers.gamepad
- simple_pendulum.controllers.gravity_compensation
- simple_pendulum.controllers.ilqr
- simple_pendulum.controllers.lqr
- simple_pendulum.controllers.open_loop
- simple_pendulum.controllers.pid
- simple_pendulum.controllers.sac
- simple_pendulum.controllers.tvlqr
Submodules
simple_pendulum.controllers.abstract_controller
Abstract Controller
Abstract controller class to which all controller classes have to adhere.
- class simple_pendulum.controllers.abstract_controller.AbstractController
Bases:
ABC
Abstract controller class. All controller should inherit from this abstract class.
- abstract get_control_output(meas_pos, meas_vel, meas_tau, meas_time)
The function to compute the control input for the pendulum actuator. Supposed to be overwritten by actual controllers. The API of this method should be adapted. Unused inputs/outputs can be set to None.
- Parameters:
- meas_pos: float
The position of the pendulum [rad]
- meas_vel: float
The velocity of the pendulum [rad/s]
- meas_tau: float
The meastured torque of the pendulum [Nm]
- meas_time: float
The collapsed time [s]
- Returns:
- des_pos: float
The desired position of the pendulum [rad]
- des_vel: float
The desired velocity of the pendulum [rad/s]
- des_tau: float
The torque supposed to be applied by the actuator [Nm]
- init(x0)
Initialize the controller. May not be necessary.
- Parameters:
- ``x0``: ``array like``
The start state of the pendulum
- set_goal(x)
Set the desired state for the controller. May not be necessary.
- Parameters:
- ``x``: ``array like``
The desired goal state of the controller
simple_pendulum.controllers.combined_controller
- class simple_pendulum.controllers.combined_controller.CombinedController(controller1, controller2, condition1, condition2, compute_both=False)
Bases:
AbstractController
Controller to combine two controllers and switch between them on conditions
- Parameters:
- controller1Controller object
First Controller
- controller2Controller object
Second Controller
- condition1function of (meas_pos, meas_vel, meas_tau, meas_time)
condition to switch to controller 1 must be a functin of the state x and the time t
- condition2function of (meas_pos, meas_vel, meas_tau, meas_time)
condition to switch to controller 2 must be a functin of the state x and the time t
- compute_bothbool
Flag whether to compute the control output for both controllers at each timestep or only for the active one
- get_control_output(meas_pos, meas_vel, meas_tau, meas_time)
The function to compute the control input for the pendulum actuator. Supposed to be overwritten by actual controllers. The API of this method should be adapted. Unused inputs/outputs can be set to None.
- Parameters:
- meas_pos: float
The position of the pendulum [rad]
- meas_vel: float
The velocity of the pendulum [rad/s]
- meas_tau: float
The meastured torque of the pendulum [Nm]
- meas_time: float
The collapsed time [s]
- Returns:
- des_pos: float
The desired position of the pendulum [rad]
- des_vel: float
The desired velocity of the pendulum [rad/s]
- des_tau: float
The torque supposed to be applied by the actuator [Nm]
- init(x0)
initialize both controllers
- set_goal(x)
Set the desired state for the controllers.
- Parameters:
- xarray like
the desired goal state of the controllers
simple_pendulum.controllers.motor_control_loop
- simple_pendulum.controllers.motor_control_loop.ak80_6(controller, kp=0.0, kd=0.0, torque_limit=1.0, dt=0.005, tf=10.0, motor_id=1, motor_type='AK80_6_V2', can_port='can0')
- Parameters:
- controllercontroller object inheriting from the abstract controller class
Calls the controller, which executes the respective control policy and returns the input torques
- kpfloat, default=0.0
Weight for position control
- kdfloat, default=0.0
Weight for velocity control
- torque_limitfloat default=1.0
torque limit for the motor [Nm]
- dtfloat, default=0.005
time step in control loop [s]
- tffloat, default=10.0
length of the experiment [s]
- motor_idint, default=1
id of the used motor
- motor_typestring, default=’AK80_6_V1p1’
type of the motor
- can_portstring, default=’can0’
can port for motor communication
- Returns:
- data_dictdict
dictionary containing the recorded data