double_pendulum.controller

Subpackages

Submodules

double_pendulum.controller.abstract_controller

class double_pendulum.controller.abstract_controller.AbstractController

Bases: ABC

Abstract controller class. All controller should inherit from this abstract class.

filter_measurement(x, last_u)
Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

last_uarray_like, shape=(2,), dtype=float

desired actuation input/motor torque, order=[u1, u2], units=[Nm]

Returns:
numpy_array

shape=(4,), dtype=float, filters state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

get_control_output(x, t=None)

The method which is called in the Simulator and real experiment loop to get the control signal from the controller. This method does:

  • filter the state

  • comput torques by calling get_control_output_

  • compute friction compensation torque (if activated)

  • comput gravity compensation torque (if activated)

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

tfloat, optional

time, unit=[s]

Returns:
array_like

shape=(2,), dtype=float actuation input/motor torque, order=[u1, u2], units=[Nm]

abstract get_control_output_(x, t=None)

The function to compute the control input for the double pendulum’s actuator(s). Supposed to be overwritten by actual controllers. The API of this method should not be changed. Unused inputs/outputs can be set to None.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

tfloat, optional

time, unit=[s] (Default value=None)

Returns:
array_like

shape=(2,), dtype=float actuation input/motor torque, order=[u1, u2], units=[Nm]

get_forecast()

Get a forecast trajectory as planned by the controller. Optional. Can be overwritten by actual controller.

Returns:
list

placeholder

list

placeholder

list

placeholder

get_friction_torque(x)

Get the torque needed to compensate for friction.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

Returns:
numpy_array

shape=(2,), dtype=float actuation input/motor torque, order=[u1, u2], units=[Nm]

get_gravity_torque(x)

Get the torque needed to compensate for gravity.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

Returns:
numpy_array

shape=(2,), dtype=float actuation input/motor torque, order=[u1, u2], units=[Nm]

get_init_trajectory()

Get an initial (reference) trajectory used by the controller. Optional. Can be overwritten by actual controller.

Returns:
list

placeholder

list

placeholder

list

placeholder

init()

Initialize function which will always be called before using the controller. In addition to the controller specific init_ method this method initialized the filter and internal logs.

init_()

Initialize the controller. Optional. Can be overwritten by actual controller. Initialize function which will always be called before using the controller.

init_filter()

Initialize the measurement filter

reset()

Reset the Controller Resets:

  • Filter

  • Friction compensation parameters

  • Gravity Compensation parameters

  • calls the controller specific reset_() function

reset_()

Reset the Controller. Optional Can be overwritten by actual controller. Function to reset parameters inside the controller.

save(save_dir)

Save controller parameters

Parameters:
save_dirstring or path object

directory where the parameters will be saved

save_(save_dir)

Save controller parameters. Optional Can be overwritten by actual controller.

Parameters:
save_dirstring or path object

directory where the parameters will be saved

set_filter_args(filt=None, x0=[3.141592653589793, 0.0, 0.0, 0.0], dt=0.001, plant=None, simulator=None, velocity_cut=-1.0, filter_kwargs={})

Set filter arguments for the measurement filter.

Parameters:
filtstring

string determining the velocity noise filter “None”: No filter “lowpass”: lowpass filter “kalman”: kalman filter “unscented_kalman”: unscented kalman filter (Default value = None)

x0array_like, shape=(4,), dtype=float,

reference state if a linearization is needed (Kalman filter), order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s] (Default value=[np.pi, 0., 0., 0.])

dtfloat

timestep, unit=[s] (Default value=0.001)

plantSymbolicDoublePendulum or DoublePendulumPlant object

A plant object containing the kinematics and dynamics of the double pendulum (Default value=None)

simulatorSimulator object

simulator object necessary for the unscented Kalman filter (Default value=None)

velocity_cutfloat

measurements smaller than this value will be set to 0. (they are assumed to be noise) For meas_noise_cut<=0.0, the measurement is not cut (Default value = -1.)

filter_kwargsdict

dictionary containing parameters for the velocity filter (Default value = {})

set_friction_compensation(damping=[0.0, 0.0], coulomb_fric=[0.0, 0.0])

Set friction terms used for the friction compensation.

Parameters:
dampingarray_like, optional

shape=(2,), dtype=float, default=[0.5, 0.5] damping coefficients of the double pendulum actuators [b1, b2], units=[kg*m/s]

coulomb_fricarray_like, optional

shape=(2,), dtype=float, default=[0.0, 0.0] coulomb friction coefficients for the double pendulum actuators [cf1, cf2], units=[Nm]

set_goal(x)

Set the desired state for the controller. Optional. Can be overwritten by actual controller.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

set_gravity_compensation(plant=None)

Provide plant for gravity compensation.

Parameters:
plantSymbolicDoublePendulum or DoublePendulumPlant object

A plant object containing the kinematics and dynamics of the double pendulum

set_parameters()

Set controller parameters. Optional. Can be overwritten by actual controller.

set_start(x)

Set the start state for the controller. Optional. Can be overwritten by actual controller.

Parameters:
x0array_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

double_pendulum.controller.combined_controller

class double_pendulum.controller.combined_controller.CombinedController(controller1, controller2, condition1, condition2, compute_both=False, verbose=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 (x, t)

condition to switch to controller 1 must be a functin of the state x and the time t

condition2function of (x, t)

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_(x, t)

The function to compute the control input for the double pendulum’s actuator(s). Will check the switch condition, potetntiolly switch the active controller and use the active controller.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

tfloat, optional

time, unit=[s]

Returns:
array_like

shape=(2,), dtype=float actuation input/motor torque, order=[u1, u2], units=[Nm]

get_forecast()

Get a forecast trajectory as planned by the controller. Uses active controller

get_init_trajectory()

Get the initial (reference) trajectory as planned by the controller. Uses active controller

init_()

initialize both controllers

reset_()

Reset controllers.

save_(save_dir)

Save controllers’ parameters.

Parameters:
save_dirstring or path object

directory where the parameters will be saved

set_goal(x)

Set the desired state for the controllers.

Parameters:
xarray like

the desired goal state of the controllers

set_parameters(controller1_pars, controller2_pars)

Set parametrers for both controllers.

Parameters:
controller1_parslist

parameters for controller 1 to be parsed to set_parameters

controller2_parslist

parameters for controller 1 to be parsed to set_parameters

set_start(x)

Set start state for the controller.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

class double_pendulum.controller.combined_controller.SimultaneousControllers(controllers, forecast_con=0)

Bases: AbstractController

Controller to combine multiple controllers and add all their outputs torques.

Parameters:
controllerslist

list containint Controller objects

forecast_conint

integer indicating which controller will be used for the forecast (Default value=0)

get_control_output_(x, t)

The function to compute the control input for the double pendulum’s actuator(s). Will sum the torques of all controller.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]

tfloat, optional

time, unit=[s]

Returns:
array_like

shape=(2,), dtype=float actuation input/motor torque, order=[u1, u2], units=[Nm]

get_forecast()

Get a forecast trajectory as planned by the controller. Uses controller indicated by self.fc_ind.

get_init_trajectory()

Get the intital (reference) trajectory as planned by the controller. Uses controller indicated by self.fc_ind.

init_()

Initialize all controllers.

set_goal(x)

Set the desired state for the controllers.

Parameters:
xarray like

the desired goal state of the controllers

set_parameters(controller_pars)

Set parameters for all controllers.

Parameters:
controller_parslist

list of lists containing the controller parameters which will be parsed to set_parameters

set_start(x)

Set start state for the controllers.

Parameters:
xarray_like, shape=(4,), dtype=float,

state of the double pendulum, order=[angle1, angle2, velocity1, velocity2], units=[rad, rad, rad/s, rad/s]