Secure your code as it's written. Use Snyk Code to scan source code in minutes - no build needed - and fix issues immediately.
for w, wname, n in zip((w1, w2, w3),
('w1', 'w2', 'w3'),
(ny, nu, ny))]
if not isinstance(g, StateSpace):
g = ss(g)
# w u
# z1 [ w1 | -w1*g ]
# z2 [ 0 | w2 ]
# z3 [ 0 | w3*g ]
# [------+--------- ]
# v [ I | -g ]
# error summer: inputs are -y and r=w
Ie = ss([], [], [], np.eye(ny))
# control: needed to "distribute" control input
Iu = ss([], [], [], np.eye(nu))
sysall = append(w1, w2, w3, Ie, g, Iu)
niw1 = w1.inputs
niw2 = w2.inputs
niw3 = w3.inputs
now1 = w1.outputs
now2 = w2.outputs
now3 = w3.outputs
q = np.zeros((niw1 + niw2 + niw3 + ny + nu, 2))
q[:, 0] = np.arange(1, q.shape[0] + 1)
motor -- instance of DcBrushedMotor
num_motors -- number of motors driving the mechanism
J -- flywheel moment of inertia in kg-m^2
G -- gear ratio from motor to flywheel
Returns:
StateSpace instance containing continuous model
"""
motor = gearbox(motor, num_motors)
A = np.array([[-(G ** 2) * motor.Kt / (motor.Kv * motor.R * J)]])
B = np.array([[G * motor.Kt / (motor.R * J)]])
C = np.array([[1]])
D = np.array([[0]])
return ct.ss(A, B, C, D)
def synth(wb1, wb2):
"""synth(wb1,wb2) -> k,gamma
wb1: S weighting frequency
wb2: KS weighting frequency
k: controller
gamma: H-infinity norm of 'design', that is, of evaluation system
with loop closed through design
"""
g = plant()
wu = ss([], [], [], np.eye(2))
wp1 = ss(weighting(wb=wb1, m=1.5, a=1e-4))
wp2 = ss(weighting(wb=wb2, m=1.5, a=1e-4))
wp = wp1.append(wp2)
k, _, info = mixsyn(g, wp, wu)
return k, info[0]
sys: controller
poles : poles for the anti-windup filter
Outputs
-------
sys_in, sys_fbk: controller in input and feedback part
"""
sys = ct.ss(sys)
Ts = sys.dt
den_old = sp.poly(la.eigvals(sys.A))
sys = ct.tf(sys)
den = sp.poly(poles)
tmp = ct.tf(den_old,den,sys.dt)
sys_in = tmp*sys
sys_in = sys_in.minreal()
sys_in = ct.ss(sys_in)
sys_fbk = 1-tmp
sys_fbk = sys_fbk.minreal()
sys_fbk = ct.ss(sys_fbk)
return sys_in, sys_fbk
def _calcGainsVel(kv, ka, qv, effort, period, velocity_delay):
# If acceleration for velocity control requires no effort, the feedback
# control gains approach zero. We special-case it here because numerical
# instabilities arise in LQR otherwise.
if ka < 1e-7:
return 0, 0
A = np.array([[-kv / ka]])
B = np.array([[1 / ka]])
C = np.array([[1]])
D = np.array([[0]])
sys = cnt.ss(A, B, C, D)
dsys = sys.sample(period)
# Assign Q and R matrices according to Bryson's rule [1]. The elements
# of q and r are tunable by the user.
#
# [1] 'Bryson's rule' in
# https://file.tavsys.net/control/state-space-guide.pdf
q = [qv] # units/s acceptable error
r = [effort] # V acceptable actuation effort
Q = np.diag(1.0 / np.square(q))
R = np.diag(1.0 / np.square(r))
K = frccnt.lqr(dsys, Q, R)
if velocity_delay > 0:
# This corrects the gain to compensate for measurement delay, which
# can be quite large as a result of filtering for some motor
def _calcGains(kv, ka, qp, qv, effort, period):
A = np.array([[0, 1], [0, -kv / ka]])
B = np.array([[0], [1 / ka]])
C = np.array([[1, 0]])
D = np.array([[0]])
sys = cnt.ss(A, B, C, D)
dsys = sys.sample(period)
# Assign Q and R matrices according to Bryson's rule [1]. The elements
# of q and r are tunable by the user.
#
# [1] "Bryson's rule" in
# https://file.tavsys.net/control/state-space-guide.pdf
q = [qp, qv] # units and units/s acceptable errors
r = [effort] # V acceptable actuation effort
Q = np.diag(1.0 / np.square(q))
R = np.diag(1.0 / np.square(r))
K = frccnt.lqr(dsys, Q, R)
kp = K[0, 0]
kd = K[0, 1]
A = np.array([[0, 1], [0, -kv / ka]])
B = np.array([[0], [1 / ka]])
C = np.array([[1, 0]])
D = np.array([[0]])
q = [qp, qv] # units and units/s acceptable errors
r = [effort] # V acceptable actuation effort
else:
A = np.array([[0]])
B = np.array([[1]])
C = np.array([[1]])
D = np.array([[0]])
q = [qp] # units acceptable error
r = [qv] # units/s acceptable error
sys = cnt.ss(A, B, C, D)
dsys = sys.sample(period)
# Assign Q and R matrices according to Bryson's rule [1]. The elements
# of q and r are tunable by the user.
#
# [1] 'Bryson's rule' in
# https://file.tavsys.net/control/state-space-guide.pdf
Q = np.diag(1.0 / np.square(q))
R = np.diag(1.0 / np.square(r))
K = frccnt.lqr(dsys, Q, R)
if position_delay > 0:
# This corrects the gain to compensate for measurement delay, which
# can be quite large as a result of filtering for some motor
# controller and sensor combinations. Note that this will result in
# an overly conservative (i.e. non-optimal) gain, because we need to
def _calcGains(kv, ka, qp, qv, effort, period):
A = np.array([[0, 1], [0, -kv / ka]])
B = np.array([[0], [1 / ka]])
C = np.array([[1, 0]])
D = np.array([[0]])
sys = cnt.ss(A, B, C, D)
dsys = sys.sample(period)
# Assign Q and R matrices according to Bryson's rule [1]. The elements
# of q and r are tunable by the user.
#
# [1] "Bryson's rule" in
# https://file.tavsys.net/control/state-space-guide.pdf
q = [qp, qv] # units and units/s acceptable errors
r = [effort] # V acceptable actuation effort
Q = np.diag(1.0 / np.square(q))
R = np.diag(1.0 / np.square(r))
K = frccnt.lqr(dsys, Q, R)
kp = K[0, 0]
kd = K[0, 1]
def plant():
"""plant() -> g
g - LTI object; 2x2 plant with a RHP zero, at s=0.5.
"""
den = [0.2, 1.2, 1]
gtf = tf([[[1], [1]],
[[2, 1], [2]]],
[[den, den],
[den, den]])
return ss(gtf)