├── .gitignore ├── arm_1link_gravity.py ├── arm_2link_todorov.py ├── arm_1link_gravity_interpol.py ├── acrobot_2link.py ├── arm_2link_todorov_gravity.py ├── arm_2link_gravity_interpol.py ├── sim_robot.py ├── RL_acrobot.py ├── README.md ├── rate_evolve.py ├── plot_utils.py ├── LICENSE └── input_rec_transform_nengo_plot.py /.gitignore: -------------------------------------------------------------------------------- 1 | # Byte-compiled / optimized / DLL files 2 | __pycache__/ 3 | *.py[cod] 4 | *$py.class 5 | 6 | # C extensions 7 | *.so 8 | 9 | # Distribution / packaging 10 | .Python 11 | env/ 12 | build/ 13 | develop-eggs/ 14 | dist/ 15 | downloads/ 16 | eggs/ 17 | .eggs/ 18 | lib/ 19 | lib64/ 20 | parts/ 21 | sdist/ 22 | var/ 23 | wheels/ 24 | *.egg-info/ 25 | .installed.cfg 26 | *.egg 27 | 28 | # PyInstaller 29 | # Usually these files are written by a python script from a template 30 | # before PyInstaller builds the exe, so as to inject date/other infos into it. 31 | *.manifest 32 | *.spec 33 | 34 | # Installer logs 35 | pip-log.txt 36 | pip-delete-this-directory.txt 37 | 38 | # Unit test / coverage reports 39 | htmlcov/ 40 | .tox/ 41 | .coverage 42 | .coverage.* 43 | .cache 44 | nosetests.xml 45 | coverage.xml 46 | *.cover 47 | .hypothesis/ 48 | 49 | # Translations 50 | *.mo 51 | *.pot 52 | 53 | # Django stuff: 54 | *.log 55 | local_settings.py 56 | 57 | # Flask stuff: 58 | instance/ 59 | .webassets-cache 60 | 61 | # Scrapy stuff: 62 | .scrapy 63 | 64 | # Sphinx documentation 65 | docs/_build/ 66 | 67 | # PyBuilder 68 | target/ 69 | 70 | # Jupyter Notebook 71 | .ipynb_checkpoints 72 | 73 | # pyenv 74 | .python-version 75 | 76 | # celery beat schedule file 77 | celerybeat-schedule 78 | 79 | # SageMath parsed files 80 | *.sage.py 81 | 82 | # dotenv 83 | .env 84 | 85 | # virtualenv 86 | .venv 87 | venv/ 88 | ENV/ 89 | 90 | # Spyder project settings 91 | .spyderproject 92 | .spyproject 93 | 94 | # Rope project settings 95 | .ropeproject 96 | 97 | # mkdocs documentation 98 | /site 99 | 100 | # mypy 101 | .mypy_cache/ 102 | -------------------------------------------------------------------------------- /arm_1link_gravity.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # (c) Nov 2016 Aditya Gilra, EPFL. 3 | 4 | """ 5 | 1-link arm without angle constraints (pendulum). 6 | Equations from: http://gribblelab.org/compneuro/5_Computational_Motor_Control_Dynamics.html 7 | Parameters from Todorov lab: Li, PhD thesis, 2006. 8 | I have the arm in a vertical plane including gravity. 9 | Inspired by (has no gravity, arm in horizontal plane): 10 | https://github.com/studywolf/control/blob/master/studywolf_control/arms/two_link/arm_python_todorov.py 11 | (c) Aditya Gilra Nov 2016. 12 | """ 13 | 14 | import numpy as np 15 | 16 | def armXY(angles): 17 | l1 = 0.31 # segment length 18 | l2 = 0.27 19 | x0 = l1 * np.cos(angles[0]) 20 | y0 = l1 * np.sin(angles[0]) 21 | return np.array((x0,y0)) 22 | 23 | def armAngles(posn): 24 | '''CAUTION: only use with valid posn, not all posn are valid for this 1-link arm!!!''' 25 | l1 = 0.31 # segment length 26 | l2 = 0.27 27 | angle0 = np.arctan2(posn[1],posn[0]) # CAUTION: use arctan2 to get 4-quadrant angle, don't use arctan 28 | return np.array([angle0]) 29 | 30 | def evolveFns(q, dq, u, XY=False, dt=None): 31 | ''' 32 | XY = True returns (delta(x,y),delta(angvelocities)) 33 | instead (delta(angles),delta(angvelocities)) 34 | dt is only used if XY=True 35 | ''' 36 | 37 | # arm model parameters 38 | m1_ = 1.4 # segment mass 39 | m2_ = 1.1 40 | l1_ = 0.31 # segment length 41 | l2_ = 0.27 42 | s1_ = 0.11 # segment center of mass 43 | s2_ = 0.16 44 | i1_ = 0.025 # segment moment of inertia 45 | i2_ = 0.045 46 | #b11_ = b22_ = b12_ = b21_ = 0.0 47 | #b11_ = b22_ = b12_ = b21_ = 0.1 48 | b11_ = 0.7 # joint friction 49 | b22_ = 0.8 50 | b12_ = 0.08 51 | b21_ = 0.08 52 | g = 9.81 # earth's acceleration due to gravity 53 | 54 | #------------------------ compute inertia I and extra torque H -------- 55 | 56 | # inertia 57 | I = i1_ + m1_*s1_**2 58 | 59 | # extra torque 60 | H = m1_*s1_*g*np.sin(q[0]) + b11_*dq[0] # gravity and drag on joint 61 | #H = b11_*dq[0] # gravity and drag on joint 62 | 63 | #------------- compute xdot = inv(I) * (torque - H) ------------ 64 | torque = u - H 65 | 66 | # return qdot and dqdot 67 | dvelocities = torque/I 68 | if XY: 69 | return (armXY(q+dq*dt)-armXY(q))/dt, dvelocities 70 | #return np.array((dvelocities,dvelocities)), dvelocities 71 | else: 72 | return dq, dvelocities 73 | #return dvelocities,dvelocities 74 | -------------------------------------------------------------------------------- /arm_2link_todorov.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # (c) Nov 2016 Aditya Gilra, EPFL. 3 | 4 | """ 5 | 2-link arm without angle constraints (pendulum). 6 | Equations from: http://gribblelab.org/compneuro/5_Computational_Motor_Control_Dynamics.html 7 | Parameters from Todorov lab: Li, PhD thesis, 2006. 8 | I have the arm in a vertical plane including gravity. 9 | Inspired by (has no gravity, arm in horizontal plane): 10 | https://github.com/studywolf/control/blob/master/studywolf_control/arms/two_link/arm_python_todorov.py 11 | (c) Aditya Gilra Nov 2016. 12 | """ 13 | 14 | import numpy as np 15 | 16 | def armXY(angles): 17 | l1 = 0.31 # segment length 18 | l2 = 0.27 19 | x0 = l1 * np.cos(angles[0]) 20 | x1 = x0 + l2 * np.cos(angles[0]+angles[1]) 21 | y0 = l1 * np.sin(angles[0]) 22 | y1 = y0 + l2 * np.sin(angles[0]+angles[1]) 23 | return np.array((x0,y0,x1,y1)) 24 | 25 | def armAngles(posn): 26 | l1 = 0.31 # segment length 27 | l2 = 0.27 28 | angle0 = np.arctan2(posn[1],posn[0]) # CAUTION: use arctan2 to get 4-quadrant angle, don't use arctan 29 | angle1 = np.arctan2((posn[3]-posn[1]),(posn[2]-posn[0])) - angle0 30 | return np.array((angle0,angle1)) 31 | 32 | def evolveFns(q, dq, u, dt, XY=False): 33 | 34 | # arm model parameters 35 | m1_ = 1.4 # segment mass 36 | m2_ = 1.1 37 | l1_ = 0.31 # segment length 38 | l2_ = 0.27 39 | s1_ = 0.11 # segment center of mass 40 | s2_ = 0.16 41 | i1_ = 0.025 # segment moment of inertia 42 | i2_ = 0.045 43 | b11_ = b22_ = b12_ = b21_ = 0.0 44 | # b11_ = 0.7 # joint friction 45 | # b22_ = 0.8 46 | # b12_ = 0.08 47 | # b21_ = 0.08 48 | 49 | #------------------------ compute inertia I and extra torque H -------- 50 | # temp vars 51 | mls = m2_* l1_*s2_ 52 | iml = i1_ + i2_ + m2_*l1_**2 53 | dd = i2_ * iml - i2_**2 54 | sy = np.sin(q[1]) 55 | cy = np.cos(q[1]) 56 | 57 | # inertia 58 | I_11 = iml + 2 * mls * cy 59 | I_12 = i2_ + mls * cy 60 | I_22 = i2_ * np.ones_like(cy) 61 | 62 | # determinant 63 | det = dd - mls**2 * cy**2 64 | 65 | # inverse inertia I1 66 | I1_11 = i2_ / det 67 | I1_12 = (-i2_ - mls * cy) / det 68 | I1_22 = (iml + 2 * mls * cy) / det 69 | 70 | # temp vars 71 | sw = np.sin(q[1]) 72 | cw = np.cos(q[1]) 73 | y = dq[0] 74 | z = dq[1] 75 | 76 | # extra torque H (Coriolis, centripetal, friction) 77 | H = np.array([-mls * (2 * y + z) * z * sw + b11_ * y + b12_ * z, 78 | mls * y**2 * sw + b22_ * z + b12_ * y]) 79 | 80 | #------------- compute xdot = inv(I) * (torque - H) ------------ 81 | torque = u.T - H 82 | 83 | # return qdot and dqdot 84 | dvelocities = np.array([(I1_11 * torque[0] + I1_12 * torque[1]), 85 | (I1_12 * torque[0] + I1_22 * torque[1])]) 86 | if XY: 87 | return (armXY(q+dq*dt)-armXY(q))/dt, dvelocities 88 | else: 89 | return dq, dvelocities 90 | -------------------------------------------------------------------------------- /arm_1link_gravity_interpol.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # (c) Nov 2016 Aditya Gilra, EPFL. 3 | 4 | """ 5 | 1-link arm without angle constraints (pendulum). 6 | Equations from: http://gribblelab.org/compneuro/5_Computational_Motor_Control_Dynamics.html 7 | Parameters from Todorov lab: Li, PhD thesis, 2006. 8 | I have the arm in a vertical plane including gravity. 9 | Inspired by (has no gravity, arm in horizontal plane): 10 | https://github.com/studywolf/control/blob/master/studywolf_control/arms/two_link/arm_python_todorov.py 11 | (c) Aditya Gilra Nov 2016. 12 | """ 13 | 14 | import numpy as np 15 | 16 | def armXY(angles): 17 | l1 = 0.31 # segment length 18 | l2 = 0.27 19 | x0 = l1 * np.cos(angles[0]) 20 | y0 = l1 * np.sin(angles[0]) 21 | return np.array((x0,y0)) 22 | 23 | def armAngles(posn): 24 | '''CAUTION: only use with valid posn, not all posn are valid for this 1-link arm!!!''' 25 | l1 = 0.31 # segment length 26 | l2 = 0.27 27 | angle0 = np.arctan2(posn[1],posn[0]) # CAUTION: use arctan2(y,x) to get 4-quadrant angle, don't use arctan 28 | return np.array([angle0]) 29 | 30 | def lin_sigmoid(x,xstart,width): 31 | '''linear sigmoid 0 till xstart, increases linearly to 1 for width.''' 32 | return np.clip(x-xstart,0,width)/width 33 | 34 | def evolveFns(q, dq, u, XY=False, dt=1e-3): # dt=1e-6 gave integration instability! 35 | ''' 36 | XY = True returns (delta(x,y),delta(angvelocities)) 37 | instead (delta(angles),delta(angvelocities)) 38 | dt is only used if XY=True 39 | ''' 40 | # arm model parameters 41 | m1_ = 1.4 # segment mass 42 | m2_ = 1.1 43 | l1_ = 0.31 # segment length 44 | l2_ = 0.27 45 | s1_ = 0.11 # segment center of mass 46 | s2_ = 0.16 47 | i1_ = 0.025 # segment moment of inertia 48 | i2_ = 0.045 49 | #b11_ = b22_ = b12_ = b21_ = 0.0 50 | #b11_ = b22_ = b12_ = b21_ = 0.1 51 | b11_ = 0.7 # joint friction 52 | b22_ = 0.8 53 | b12_ = 0.08 54 | b21_ = 0.08 55 | g = 9.81 # earth's acceleration due to gravity 56 | resistance = 0. # resistance torque coeff beyond certain angle 57 | 58 | #------------------------ compute inertia I and extra torque H -------- 59 | 60 | # inertia 61 | I = i1_ + m1_*s1_**2 62 | 63 | # extra torque 64 | H = m1_*s1_*g*np.sin(q[0]) + b11_*dq[0] # gravity and drag on joint 65 | #H = b11_*dq[0] # gravity and drag on joint 66 | 67 | #------------- compute xdot = inv(I) * (torque - H) ------------ 68 | torque = u - H 69 | # torque cannot be applied in the angle's direction beyond the angle's limit, 70 | # friction then decays the angular velocity back to zero. 71 | torque = - H + u * (1 - (u>0)*lin_sigmoid(q,np.pi/2.,np.pi/4.) - (u<0)*lin_sigmoid(-q,np.pi/2.,np.pi/4) ) \ 72 | # strong oscillations! 73 | #torque = u - H + resistance * (-np.float(q>np.pi/2)*np.abs(q-np.pi/2) + np.float(q<-np.pi/2)*np.abs(q+np.pi/2)) 74 | 75 | # return qdot and dqdot 76 | dvelocities = torque/I 77 | 78 | ## soft limits on angles 79 | #dq *= 1 - lin_sigmoid(q,np.pi/2.,np.pi/4.) - lin_sigmoid(-q,np.pi/2.,np.pi/4) 80 | qnew = q + dq*dt 81 | ## soft limits on angular velocity 82 | #dvelocities *= 1 - lin_sigmoid(dq,3*np.pi,np.pi) - lin_sigmoid(-dq,3*np.pi,np.pi) 83 | dqnew = dq + dvelocities*dt 84 | ## hard limits on angular velocity 85 | #dqnew = np.clip(dqnew,-3*np.pi,3*np.pi) 86 | ## soft limits on angular velocity based on angle 87 | #dqnew *= 1 - lin_sigmoid(q,np.pi/2.,np.pi/4.) - lin_sigmoid(-q,np.pi/2.,np.pi/4) 88 | ## soft limits on angular velocity based on angle and direction of angular velocity 89 | ## IMPORTANT: Actually this will have the time scale of the integration ~1ms!!! 90 | #dqnew *= 1 - np.float(dq>0)*lin_sigmoid(q,np.pi/2.,np.pi/4.) - np.float(dq<0)*lin_sigmoid(-q,np.pi/2.,np.pi/4) 91 | 92 | if XY: 93 | #return (armXY(q+dq*dt)-armXY(q))/dt, dvelocities 94 | return (armXY(qnew)-armXY(q))/dt, (dqnew-dq)/dt 95 | else: 96 | #return dq, dvelocities 97 | return (qnew-q)/dt, (dqnew-dq)/dt 98 | -------------------------------------------------------------------------------- /acrobot_2link.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # (c) Nov 2016 Aditya Gilra, EPFL. 3 | 4 | """ 5 | 2-link acrobot without angle constraints (pendulum). 6 | Equations from: http://gribblelab.org/compneuro/5_Computational_Motor_Control_Dynamics.html 7 | Parameters from Sutton 1996. 8 | I have the arm in a vertical plane including gravity. 9 | Inspired by (has no gravity, arm in horizontal plane): 10 | https://github.com/studywolf/control/blob/master/studywolf_control/arms/two_link/arm_python_todorov.py 11 | (c) Aditya Gilra Dec 2016. 12 | """ 13 | 14 | import numpy as np 15 | 16 | def armXY(angles): 17 | l1 = 1. # segment length 18 | l2 = 1. 19 | x0 = l1 * np.cos(angles[0]) 20 | x1 = x0 + l2 * np.cos(angles[0]+angles[1]) 21 | y0 = l1 * np.sin(angles[0]) 22 | y1 = y0 + l2 * np.sin(angles[0]+angles[1]) 23 | return np.array((x0,y0,x1,y1)) 24 | 25 | def armAngles(posn): 26 | '''CAUTION: only use with valid posn, not all posn are valid for this 2-link arm!!!''' 27 | l1 = 1. # segment length 28 | l2 = 1. 29 | angle0 = np.arctan2(posn[1],posn[0]) # CAUTION: use arctan2 to get 4-quadrant angle, don't use arctan 30 | angle1 = np.arctan2((posn[3]-posn[1]),(posn[2]-posn[0])) - angle0 31 | return np.array((angle0,angle1)) 32 | 33 | def lin_sigmoid(x,xstart,width): 34 | '''linear sigmoid 0 till xstart, increases linearly to 1 for width.''' 35 | return np.clip(x-xstart,0,width)/width 36 | 37 | def evolveFns(q, dq, u, XY=False, dt=1e-3): # dt of 1e-6 can give integration instability 38 | ''' 39 | XY = True returns (delta(x,y),delta(angvelocities)) 40 | instead (delta(angles),delta(angvelocities)) 41 | dt is only used if XY=True 42 | ''' 43 | 44 | q = (q + np.pi)%(2*np.pi) - np.pi # ensure that angles remain between -pi and pi. 45 | # arm model parameters 46 | m1_ = 1. # segment mass 47 | m2_ = 1. 48 | l1_ = 1. # segment length 49 | l2_ = 1. 50 | s1_ = 0.5 # segment center of mass 51 | s2_ = 0.5 52 | i1_ = 1. # segment moment of inertia 53 | i2_ = 1. 54 | b11_ = b22_ = b12_ = b21_ = 0.0 55 | #b11_ = 0.7 # joint friction 56 | #b22_ = 0.8 57 | #b12_ = 0.08 58 | #b21_ = 0.08 59 | g = 9.8 # earth's acceleration due to gravity 60 | drag_coeff = 10. # drag coeff of friction at the angle limits 61 | 62 | #------------------------ compute inertia I and extra torque H -------- 63 | # temp vars 64 | mls = m2_* l1_*s2_ 65 | iml = i1_ + i2_ + m2_*l1_**2 66 | dd = i2_ * iml - i2_**2 67 | sy = np.sin(q[1]) 68 | cy = np.cos(q[1]) 69 | 70 | # inertia 71 | #I_11 = iml + 2 * mls * cy 72 | #I_12 = i2_ + mls * cy 73 | #I_22 = i2_ * np.ones_like(cy) 74 | # aditya modified: 75 | I_11 = iml + 2 * mls * cy + m1_*s1_**2 + m2_*s2_**2 76 | I_12 = i2_ + mls * cy + m2_*s2_**2 77 | I_22 = i2_ * np.ones_like(cy) + m2_*s2_**2 78 | 79 | # determinant 80 | #det = dd - mls**2 * cy**2 81 | det = I_11*I_22 - I_12**2 82 | 83 | # inverse inertia I1 84 | #I1_11 = i2_ / det 85 | #I1_12 = (-i2_ - mls * cy) / det 86 | #I1_22 = (iml + 2 * mls * cy) / det 87 | I1_11 = I_22 / det 88 | I1_12 = -I_12 / det 89 | I1_22 = I_11 / det 90 | 91 | # temp vars 92 | sw = np.sin(q[1]) 93 | cw = np.cos(q[1]) 94 | y = dq[0] 95 | z = dq[1] 96 | 97 | # extra torque H (Coriolis, centripetal, friction, gravity-aditya) 98 | H = np.array([-mls * (2 * y + z) * z * sw + b11_ * y + b12_ * z + (m1_*s1_+m2_*l1_)*g*np.sin(q[0]) + m2_*s2_*g*np.sin(q[0]+q[1]) , 99 | mls * y**2 * sw + b22_ * z + b12_ * y + m2_*s2_*g*np.sin(q[0]+q[1]) ]) 100 | #H = np.array([-mls * (2 * y + z) * z * sw + b11_ * y + b12_ * z + m1_*s1_*g*np.sin(q[0]), 101 | # mls * y**2 * sw + b22_ * z + b12_ * y + m2_*s2_*g*np.sin(q[0]+q[1]) ]) 102 | 103 | #------------- compute xdot = inv(I) * (torque - H) ------------ 104 | torque = u.T - H 105 | 106 | # torque cannot be applied in the angle's direction beyond the angle's limit, 107 | # drag friction only at angle limits which decays the angular velocity back to zero. 108 | # must use np.float() to convert boolean to 0/1. 109 | torque = np.zeros(2) 110 | for i in range(2): 111 | highlim = lin_sigmoid(q[i],np.pi/2.,np.pi/4.) 112 | lowlim = lin_sigmoid(-q[i],np.pi/2.,np.pi/4.) 113 | torque[i] = - H[i] + u[i] * \ 114 | (1 - np.float(u[i]>0)*highlim - np.float(u[i]<0)*lowlim) \ 115 | - drag_coeff*dq[i] * \ 116 | (np.float(dq[i]>0)*highlim + np.float(dq[i]<0)*lowlim) 117 | 118 | # return qdot and dqdot 119 | dvelocities = np.array([(I1_11 * torque[0] + I1_12 * torque[1]), 120 | (I1_12 * torque[0] + I1_22 * torque[1])]) 121 | 122 | qnew = q + dq*dt 123 | #qnew[1] = np.clip(qnew[1],-0.5*np.pi,0.8*np.pi) 124 | dqnew = dq + dvelocities*dt 125 | dqnew[0] = np.clip(dqnew[0],-4*np.pi,4*np.pi) 126 | dqnew[1] = np.clip(dqnew[1],-9*np.pi,9*np.pi) 127 | 128 | if XY: 129 | return (armXY(qnew)-armXY(q))/dt, (dqnew-dq)/dt 130 | else: 131 | return (qnew-q)/dt, (dqnew-dq)/dt 132 | -------------------------------------------------------------------------------- /arm_2link_todorov_gravity.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # (c) Nov 2016 Aditya Gilra, EPFL. 3 | 4 | """ 5 | 2-link arm with angle constraints (pendulum). 6 | Equations from: http://gribblelab.org/compneuro/5_Computational_Motor_Control_Dynamics.html 7 | Parameters from Todorov lab: Li, PhD thesis, 2006. 8 | I have the arm in a vertical plane including gravity. 9 | Inspired by (has no gravity, arm in horizontal plane): 10 | https://github.com/studywolf/control/blob/master/studywolf_control/arms/two_link/arm_python_todorov.py 11 | I also added constraints so that each joint receives less torque if joint angle > pi/2 on either side, 12 | going to 0 once joint angle > 3pi/4 on either side. 13 | (c) Aditya Gilra Nov 2016. 14 | Used in Gilra and Gerstner, https://arxiv.org/abs/1702.06463, Feb 2017. 15 | """ 16 | 17 | import numpy as np 18 | 19 | def armXY(angles): 20 | # CAUTION: I added np.pi/2 in below armAngles(), so this fn is not consistent with that fn! 21 | l1 = 0.31 # segment length 22 | l2 = 0.27 23 | x0 = l1 * np.cos(angles[0]) 24 | x1 = x0 + l2 * np.cos(angles[0]+angles[1]) 25 | y0 = l1 * np.sin(angles[0]) 26 | y1 = y0 + l2 * np.sin(angles[0]+angles[1]) 27 | return np.array((x0,y0,x1,y1)) 28 | 29 | def armAngles(posn): 30 | '''CAUTION: only use with valid posn, not all posn are valid for this 2-link arm!!!''' 31 | l1 = 0.31 # segment length 32 | l2 = 0.27 33 | angle0 = np.arctan2(posn[1],posn[0])+np.pi/2 # CAUTION: use arctan2 to get 4-quadrant angle, don't use arctan 34 | # adding np.pi/2 to both angles, so that downwards position is angle=0 35 | angle1 = np.arctan2((posn[3]-posn[1]),(posn[2]-posn[0]))+np.pi/2 - angle0 36 | return np.array((angle0,angle1)) 37 | 38 | def armAnglesEnd(endposn): 39 | '''Given only the endposn, calculate both link positions. 40 | Don't give y=0, but x=0 wprks fine''' 41 | l1 = 0.31 # segment length 42 | l2 = 0.27 43 | x1,y1 = endposn 44 | A = (x1**2 + y1**2 - l2**2 + l1**2)/2./y1 45 | B = -x1/y1 46 | x0a = (-2*A*B + np.sqrt(4*A**2*B**2-4*(1+B**2)*(A**2-l1**2)))/2./(1+B**2) 47 | x0b = (-2*A*B - np.sqrt(4*A**2*B**2-4*(1+B**2)*(A**2-l1**2)))/2./(1+B**2) 48 | y0a = A+B*x0a 49 | y0b = A+B*x0b 50 | if y0a0)*lin_sigmoid(q[i],np.pi/2.,np.pi/4.) \ 133 | - np.float(u[i]<0)*lin_sigmoid(-q[i],np.pi/2.,np.pi/4) ) 134 | 135 | # return qdot and dqdot 136 | dvelocities = np.array([(I1_11 * torque[0] + I1_12 * torque[1]), 137 | (I1_12 * torque[0] + I1_22 * torque[1])]) 138 | if XY: 139 | return (armXY(q+dq*dt)-armXY(q))/dt, dvelocities 140 | else: 141 | return dq, dvelocities 142 | -------------------------------------------------------------------------------- /arm_2link_gravity_interpol.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # (c) Nov 2016 Aditya Gilra, EPFL. 3 | 4 | """ 5 | 1-link arm without angle constraints (pendulum). 6 | Equations from: http://gribblelab.org/compneuro/5_Computational_Motor_Control_Dynamics.html 7 | Parameters from Todorov lab: Li, PhD thesis, 2006. 8 | I have the arm in a vertical plane including gravity. 9 | Inspired by (has no gravity, arm in horizontal plane): 10 | https://github.com/studywolf/control/blob/master/studywolf_control/arms/two_link/arm_python_todorov.py 11 | (c) Aditya Gilra Nov 2016. 12 | """ 13 | 14 | import numpy as np 15 | 16 | def armXY(angles): 17 | l1 = 0.31 # segment length 18 | l2 = 0.27 19 | x0 = l1 * np.cos(angles[0]) 20 | x1 = x0 + l2 * np.cos(angles[0]+angles[1]) 21 | y0 = l1 * np.sin(angles[0]) 22 | y1 = y0 + l2 * np.sin(angles[0]+angles[1]) 23 | return np.array((x0,y0,x1,y1)) 24 | 25 | def armAngles(posn): 26 | l1 = 0.31 # segment length 27 | l2 = 0.27 28 | angle0 = np.arctan2(posn[1],posn[0]) # CAUTION: use arctan2 to get 4-quadrant angle, don't use arctan 29 | angle1 = np.arctan2((posn[3]-posn[1]),(posn[2]-posn[0])) - angle0 30 | return np.array((angle0,angle1)) 31 | 32 | def lin_sigmoid(x,xstart,width): 33 | '''linear sigmoid 0 till xstart, increases linearly to 1 for width.''' 34 | return np.clip(x-xstart,0,width)/width 35 | 36 | def evolveFns(q, dq, u, XY=False, dt=1e-3): # dt=1e-6 gave integration instability! 37 | ''' 38 | XY = True returns (delta(x,y),delta(angvelocities)) 39 | instead (delta(angles),delta(angvelocities)) 40 | dt is only used if XY=True 41 | ''' 42 | # arm model parameters 43 | m1_ = 1.4 # segment mass 44 | m2_ = 1.1 45 | l1_ = 0.31 # segment length 46 | l2_ = 0.27 47 | s1_ = 0.11 # segment center of mass 48 | s2_ = 0.16 49 | i1_ = 0.025 # segment moment of inertia 50 | i2_ = 0.045 51 | #b11_ = b22_ = b12_ = b21_ = 0.0 52 | #b11_ = b22_ = b12_ = b21_ = 0.1 53 | b11_ = 0.7 # joint friction 54 | b22_ = 0.8 55 | b12_ = 0.08 56 | b21_ = 0.08 57 | g = 9.81 # earth's acceleration due to gravity 58 | resistance = 0. # resistance torque coeff beyond certain angle 59 | 60 | #------------------------ compute inertia I and extra torque H -------- 61 | 62 | # temp vars 63 | mls = m2_* l1_*s2_ 64 | iml = i1_ + i2_ + m2_*l1_**2 65 | dd = i2_ * iml - i2_**2 66 | sy = np.sin(q[1]) 67 | cy = np.cos(q[1]) 68 | 69 | ## inertia -- independent inertia terms for each link (no matrix inversion) 70 | #I = np.array((i1_ + m1_*s1_**2, i2_ + m2_*s2_**2)) 71 | 72 | # inertia matrix 73 | I_11 = iml + 2 * mls * cy + m1_*s1_**2 + m2_*s2_**2 74 | I_12 = i2_ + mls * cy + m2_*s2_**2 75 | I_22 = i2_ * np.ones_like(cy) + m2_*s2_**2 76 | 77 | # determinant 78 | #det = dd - mls**2 * cy**2 79 | det = I_11*I_22 - I_12**2 80 | 81 | # inverse of inertia matrix 82 | #I1_11 = i2_ / det 83 | #I1_12 = (-i2_ - mls * cy) / det 84 | #I1_22 = (iml + 2 * mls * cy) / det 85 | I1_11 = I_22 / det 86 | I1_12 = -I_12 / det 87 | I1_22 = I_11 / det 88 | 89 | # temp vars 90 | sw = np.sin(q[1]) 91 | cw = np.cos(q[1]) 92 | y = dq[0] 93 | z = dq[1] 94 | 95 | # extra torque H (Coriolis, centripetal, friction, gravity-aditya) 96 | H = np.array([-mls * (2 * y + z) * z * sw + b11_ * y + b12_ * z + (m1_*s1_+m2_*l1_)*g*np.sin(q[0]) + m2_*s2_*g*np.sin(q[0]+q[1]) , 97 | mls * y**2 * sw + b22_ * z + b12_ * y + m2_*s2_*g*np.sin(q[0]+q[1]) ]) 98 | 99 | ## extra torque H (friction matrix, gravity-aditya) 100 | #H = np.array([b11_ * y + b12_ * z + (m1_*s1_+m2_*l1_)*g*np.sin(q[0]) , 101 | # b22_ * z + b12_ * y + m2_*s2_*g*np.sin(q[0]+q[1]) ]) 102 | 103 | ## extra torque: gravity and independent friction on each joint 104 | #H = np.array((m1_*s1_*g*np.sin(q[0]) + b11_*dq[0], m2_*s2_*g*np.sin(q[1]) + b22_*dq[1])) 105 | 106 | #------------- compute xdot = inv(I) * (torque - H) ------------ 107 | #torque = u - H 108 | # torque cannot be applied in the angle's direction beyond the angle's limit, 109 | # friction then decays the angular velocity back to zero. 110 | # must use np.float() to convert boolean to 0/1. 111 | torque = np.zeros(2) 112 | for i in range(2): 113 | torque[i] = - H[i] + u[i] * \ 114 | (1 - np.float(u[i]>0)*lin_sigmoid(q[i],np.pi/2.,np.pi/4.) \ 115 | - np.float(u[i]<0)*lin_sigmoid(-q[i],np.pi/2.,np.pi/4) ) 116 | # strong oscillations! 117 | #torque = u - H + resistance * (-np.float(q>np.pi/2)*np.abs(q-np.pi/2) + np.float(q<-np.pi/2)*np.abs(q+np.pi/2)) 118 | 119 | ## return qdot and dqdot -- does not take inverse of inertia matrix 120 | #dvelocities = torque/I # element-wise division 121 | 122 | # uses inverse of inertia matrix 123 | dvelocities = np.array([(I1_11 * torque[0] + I1_12 * torque[1]), 124 | (I1_12 * torque[0] + I1_22 * torque[1])]) 125 | 126 | ## soft limits on angles 127 | #dq *= 1 - lin_sigmoid(q,np.pi/2.,np.pi/4.) - lin_sigmoid(-q,np.pi/2.,np.pi/4) 128 | qnew = q + dq*dt 129 | ## soft limits on angular velocity 130 | #dvelocities *= 1 - lin_sigmoid(dq,3*np.pi,np.pi) - lin_sigmoid(-dq,3*np.pi,np.pi) 131 | dqnew = dq + dvelocities*dt 132 | ## hard limits on angular velocity 133 | #dqnew = np.clip(dqnew,-3*np.pi,3*np.pi) 134 | ## soft limits on angular velocity based on angle 135 | #dqnew *= 1 - lin_sigmoid(q,np.pi/2.,np.pi/4.) - lin_sigmoid(-q,np.pi/2.,np.pi/4) 136 | ## soft limits on angular velocity based on angle and direction of angular velocity 137 | ## IMPORTANT: Actually this will have the time scale of the integration ~1ms!!! 138 | #dqnew *= 1 - np.float(dq>0)*lin_sigmoid(q,np.pi/2.,np.pi/4.) - np.float(dq<0)*lin_sigmoid(-q,np.pi/2.,np.pi/4) 139 | 140 | if XY: 141 | return (armXY(qnew)-armXY(q))/dt, (dqnew-dq)/dt 142 | else: 143 | return (qnew-q)/dt, (dqnew-dq)/dt 144 | -------------------------------------------------------------------------------- /sim_robot.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # (c) Sep 2015 Aditya Gilra, EPFL. 3 | 4 | """ 5 | communicating with V-REP or 2-link pendulum arm models 6 | written by Aditya Gilra (c) Oct 2016. 7 | communicating to/from vrep simulator adapted from : 8 | https://studywolf.wordpress.com/2016/04/18/using-vrep-for-simulation-of-force-controlled-models/ 9 | https://github.com/studywolf/blog/blob/master/VREP/two_link_arm/vrep_twolink_controller.py 10 | """ 11 | 12 | import numpy as np 13 | # pickle constructs the object in memory, use shelve for direct to/from disk 14 | import shelve, contextlib 15 | 16 | def sim_robot(robotType,funcType,reloadrobotsim,robDataFileName,\ 17 | Tmax=0.,inpfn=None,trialclamp=False,Tperiod=0.,Tclamp=0.,simdt=0.001): 18 | 19 | if reloadrobotsim: 20 | with contextlib.closing( 21 | shelve.open(robDataFileName+'_'+robotType+'.shelve', 'r') 22 | ) as data_dict: 23 | robtrange = data_dict['robtrange'] 24 | rateEvolveProbe = data_dict['angles'] 25 | #torqueArray = data_dict['torque'] # no need to load this 26 | else: 27 | if 'robot2' in funcType: 28 | N = 4 # 4-dim system 29 | joint_names = ['shoulder', 'elbow'] 30 | else: 31 | N = 2 # 2-dim system 32 | joint_names = ['shoulder'] 33 | zerosNby2 = np.zeros(N//2) 34 | ###################################### VREP robot arm ##################################### 35 | if robotType == 'V-REP': 36 | robotdt = .02 # we run the robot simulator faster as vrep is slow and dynamics is smooth 37 | # and interpolate when feeding to nengo 38 | import vrep 39 | # close any open connections 40 | vrep.simxFinish(-1) 41 | # Connect to the V-REP continuous server 42 | portnum = 19997 43 | clientID = vrep.simxStart('127.0.0.1', portnum, True, True, 500, 5) 44 | 45 | if clientID != -1: # if we connected successfully 46 | print ('Connected to V-REP remote API server on port',portnum) 47 | 48 | # --------------------- Setup the simulation 49 | 50 | vrep.simxSynchronous(clientID,True) 51 | 52 | # get handles to each joint 53 | joint_handles = [vrep.simxGetObjectHandle(clientID, 54 | name, vrep.simx_opmode_blocking)[1] for name in joint_names] 55 | 56 | # set vrep time step 57 | vrep.simxSetFloatingParameter(clientID, 58 | vrep.sim_floatparam_simulation_time_step, 59 | robotdt, 60 | vrep.simx_opmode_oneshot) 61 | 62 | 63 | # start simulation in blocking mode 64 | vrep.simxStartSimulation(clientID, 65 | vrep.simx_opmode_blocking) 66 | simrun = True 67 | 68 | robtrange = np.arange(0,Tmax,robotdt) 69 | rateEvolveProbe = np.zeros(shape=(len(robtrange),N)) 70 | torqueArray = np.zeros(shape=(len(robtrange),N//2)) 71 | for it,t in enumerate(robtrange): 72 | torquet = inpfn(t)[N//2:] # zeros to dq/dt, torque to dv/dt 73 | torqueArray[it,:] = torquet 74 | 75 | if trialclamp and (t%Tperiod)>(Tperiod-Tclamp): 76 | if simrun: 77 | # stop the vrep simulation 78 | vrep.simxStopSimulation(clientID, 79 | vrep.simx_opmode_blocking) 80 | simrun = False 81 | rateEvolveProbe[it,:N//2] = zerosNby2 82 | rateEvolveProbe[it,N//2:] = zerosNby2 83 | else: 84 | if not simrun: 85 | # start simulation in blocking mode 86 | vrep.simxStartSimulation(clientID, 87 | vrep.simx_opmode_blocking) 88 | simrun = True 89 | # apply the torque to the vrep arm 90 | # vrep has a crazy way of setting the torque: 91 | # the torque is applied in target velocity direction 92 | # until target velocity is reached, 93 | # so we need to set the sign of the target velocity correct, 94 | # with its value very high so that it is never reached, 95 | # and then set the torque magnitude as desired. 96 | for ii,joint_handle in enumerate(joint_handles): 97 | # first we set the target velocity sign same as the torque sign 98 | _ = vrep.simxSetJointTargetVelocity(clientID, 99 | joint_handle, 100 | np.sign(torquet[ii])*9e4, # target velocity 101 | vrep.simx_opmode_blocking) 102 | if _ !=0 : raise Exception() 103 | 104 | # second we set the torque to abs value desired 105 | vrep.simxSetJointForce(clientID, 106 | joint_handle, 107 | abs(torquet[ii]), # 2D torque to apply i.e. \vec{u}(t) 108 | vrep.simx_opmode_blocking) 109 | if _ !=0 : raise Exception() 110 | 111 | # step vrep simulation by a time step 112 | vrep.simxSynchronousTrigger(clientID) 113 | 114 | # get updated joint angles and velocity from vrep 115 | q = np.zeros(len(joint_handles)) # 2D output \vec{x}(t) 116 | v = np.zeros(len(joint_handles)) 117 | for ii,joint_handle in enumerate(joint_handles): 118 | # get the joint angles 119 | _, q[ii] = vrep.simxGetJointPosition(clientID, 120 | joint_handle, 121 | vrep.simx_opmode_blocking) 122 | if _ !=0 : raise Exception() 123 | # get the joint velocity 124 | _, v[ii] = vrep.simxGetObjectFloatParameter(clientID, 125 | joint_handle, 126 | 2012, # parameter ID for angular velocity of the joint 127 | vrep.simx_opmode_blocking) 128 | if _ !=0 : raise Exception() 129 | rateEvolveProbe[it,:N//2] = q 130 | rateEvolveProbe[it,N//2:] = v 131 | 132 | if it%1000==0: 133 | print(it,'time steps, i.e.',t,'s of vrep sim are over.') 134 | 135 | # stop the vrep simulation 136 | vrep.simxStopSimulation(clientID, vrep.simx_opmode_blocking) 137 | 138 | # send a blocking command, so that all previous commands finish 139 | # redundant perhaps, since stop simulation is also blocking 140 | vrep.simxGetPingTime(clientID) 141 | 142 | # close the V-REP connection 143 | vrep.simxFinish(clientID) 144 | 145 | else: 146 | raise Exception('Connection to V-REP remote API server failed') 147 | sys.exit(1) 148 | myarm = None 149 | ######################################### PENDULUM ARM ###################################### 150 | elif robotType == 'pendulum': 151 | robotdt = simdt # pendulum simulation is fast enough, no need of slower robotdt 152 | if funcType in ('robot1_gravity','robot1XY_gravity'): 153 | from arm_1link_gravity import evolveFns,armXY,armAngles 154 | elif funcType in ('robot1_gravity_interpol','robot1XY_gravity_interpol'): 155 | from arm_1link_gravity_interpol import evolveFns,armXY,armAngles 156 | elif funcType in ('robot2_gravity_interpol'): 157 | from arm_2link_gravity_interpol import evolveFns,armXY,armAngles 158 | elif funcType == 'robot2_todorov': 159 | from arm_2link_todorov import evolveFns,armXY,armAngles 160 | elif funcType in ('robot2_todorov_gravity','robot2XY_todorov_gravity'): 161 | from arm_2link_todorov_gravity import evolveFns,armXY,armAngles 162 | elif funcType in ('acrobot2_gravity','acrobot2XY_gravity'): 163 | from acrobot_2link import evolveFns,armXY,armAngles 164 | else: 165 | raise Exception('Choose one- or two-link robot') 166 | robtrange = np.arange(0,Tmax,robotdt) 167 | torqueArray = np.zeros(shape=(len(robtrange),N//2)) 168 | 169 | qzero = np.zeros(N//2) # angles and angvelocities at start are subtracted below 170 | dqzero = np.zeros(N//2) # start from zero, fully downward position initially 171 | q = np.copy(qzero) # must copy, else pointer is used 172 | dq = np.copy(dqzero) 173 | 174 | if 'XY' in funcType: # for XY robot, return (positions,angvelocities), though angles are evolved 175 | rateEvolveProbe = np.zeros(shape=(len(robtrange),N+N//2)) 176 | def set_robot_state(angles,velocities): 177 | rateEvolveProbe[it,:N] = armXY(angles) 178 | rateEvolveProbe[it,N:] = (velocities-dqzero) 179 | else: # for usual robot return (angles,angvelocities) 180 | rateEvolveProbe = np.zeros(shape=(len(robtrange),N)) 181 | def set_robot_state(angles,velocities): 182 | #rateEvolveProbe[it,:N//2] = ((angles+np.pi)%(2*np.pi)-qzero) 183 | # wrap angles within -pi and pi 184 | # not arctan(tan()) as it returns within -pi/2 and pi/2 185 | rateEvolveProbe[it,:N//2] = (angles-qzero) # don't wrap angles, limit them or use trials so they don't run away 186 | # subtract out the start position 187 | rateEvolveProbe[it,N//2:] = (velocities-dqzero) 188 | 189 | for it,t in enumerate(robtrange): 190 | if trialclamp and (t%Tperiod)>(Tperiod-Tclamp): 191 | # at the end of each trial, bring arm to start position 192 | q = np.copy(qzero) # must copy, else pointer is used 193 | dq = np.copy(dqzero) 194 | else: 195 | #torquet = inpfn(t)[N//2:] # torque to dv/dt ([:N//2] has only zeros for dq/dt) -- for ff+rec 196 | torquet = inpfn(t) # torque to dv/dt -- for rec 197 | torqueArray[it,:] = torquet 198 | qdot,dqdot = evolveFns(q,dq,torquet) 199 | q += qdot*robotdt 200 | dq += dqdot*robotdt 201 | set_robot_state(q,dq) 202 | 203 | else: 204 | raise Exception('Choose robotType') 205 | sys.exit(1) 206 | 207 | with contextlib.closing( 208 | # 'c' opens for read/write, creating if non-existent 209 | shelve.open(robDataFileName+'_'+robotType+'.shelve', 'c', protocol=-1) 210 | ) as data_dict: 211 | data_dict['robtrange'] = robtrange 212 | data_dict['angles'] = rateEvolveProbe 213 | data_dict['torque'] = torqueArray 214 | 215 | return robtrange,rateEvolveProbe,evolveFns,armAngles 216 | -------------------------------------------------------------------------------- /RL_acrobot.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | # -*- coding: utf-8 -*- 3 | 4 | import sys 5 | import matplotlib as mpl 6 | # must be called before any pylab import, matplotlib calls 7 | mpl.use('QT4Agg') 8 | import matplotlib.pyplot as plt 9 | import numpy as np 10 | import matplotlib.animation as animation 11 | from plot_utils import * 12 | 13 | # choose whether to load and plot previous learned torque(t), 14 | # or learn anew using reinforcement learning 15 | loadOld = False 16 | #loadOld = True 17 | 18 | ## choose one arm / acrobot model out of the below 19 | #bot = 'arm_1link' 20 | bot = 'arm_2link' 21 | #bot = 'acrobot_2link' 22 | 23 | ## choose one task out of the below: 24 | #task = 'reach1' 25 | #task = 'reach2' 26 | #task = 'reach3' 27 | task = 'swing' 28 | #task = 'swing2' 29 | 30 | #np.random.seed(1) 31 | np.random.seed(2) # seed 2 for reach1 32 | 33 | if bot == 'arm_1link': 34 | from arm_1link_gravity import evolveFns,armXY,armAngles 35 | N = 2 36 | setpoint = 0.1 37 | torques = np.array([div_torq,0.,-div_torq]) 38 | action0 = 1 # index for zero torque at t=0 39 | len_actions = 3 40 | acrobot = False 41 | elif bot == 'arm_2link': 42 | from arm_2link_todorov_gravity import evolveFns,armXY,armAngles 43 | N = 4 # 2-link arm 44 | if task == 'swing': 45 | div_torq = 5. 46 | max_dq = np.array([10.,10.]) # with friction (B matrix) 47 | # for swing task allow torques to only elbow joint 48 | torques = np.array([(0.,div_torq),(0.,0.),(0.,-div_torq)]) 49 | action0 = 1 # index for zero torque at t=0 50 | len_actions = 3 51 | setpointX = 0.3 52 | setpointY = -0.3 53 | elif task == 'swing2': 54 | div_torq = 5. 55 | max_dq = np.array([10.,10.]) # with friction (B matrix) 56 | # for swing task allow torques to only elbow joint 57 | torques = np.array([(0.,div_torq),(0.,0.),(0.,-div_torq)]) 58 | action0 = 1 # index for zero torque at t=0 59 | len_actions = 3 60 | setpointX = 0.1 61 | setpointY = -0.25 62 | elif task == 'reach1': 63 | div_torq = 5. 64 | # important to set high-enough bounds for max velocity, else indices can go out of range 65 | # yet small-enough to explore in num_tiles tiling 66 | max_dq = np.array([10.,10.]) # with friction (B matrix) 67 | # for reach task, allow torques to both joints 68 | torques = np.array([(div_torq,div_torq),(0.,0.),(-div_torq,-div_torq)]) 69 | action0 = 1 # index for zero torque at t=0 70 | len_actions = 3 71 | setpointX = 0.35 72 | setpointY = -0.2 73 | elif task == 'reach2': 74 | div_torq = 5. 75 | # important to set high-enough bounds for max velocity, else indices can go out of range 76 | # yet small-enough to explore in num_tiles tiling 77 | max_dq = np.array([10.,10.]) # with friction (B matrix) 78 | # for reach task, allow torques to both joints 79 | torques = np.array([(-div_torq,-div_torq),(-div_torq,0.),(-div_torq,div_torq), 80 | (0.,-div_torq),(0.,0.),(0,div_torq), 81 | (div_torq,-div_torq),(div_torq,0.),(div_torq,div_torq),]) 82 | action0 = 4 # index for zero torque at t=0 83 | len_actions = 9 84 | setpointX = 0.5 85 | setpointY = 0.1 86 | elif task == 'reach3': 87 | div_torq = 5. 88 | # important to set high-enough bounds for max velocity, else indices can go out of range 89 | # yet small-enough to explore in num_tiles tiling 90 | max_dq = np.array([10.,10.]) # with friction (B matrix) 91 | # for reach task, allow torques to both joints 92 | torques = np.array([(-div_torq,-div_torq),(-div_torq,0.),(-div_torq,div_torq), 93 | (0.,-div_torq),(0.,0.),(0,div_torq), 94 | (div_torq,-div_torq),(div_torq,0.),(div_torq,div_torq),]) 95 | action0 = 4 # index for zero torque at t=0 96 | len_actions = 9 97 | setpointX = 0.5 98 | setpointY = -0.2 99 | else: 100 | print('please choose a task') 101 | sys.exit(1) 102 | acrobot = False 103 | robotdt = 0.01 # evolve with this time step 104 | animdt = 0.1 # time step for an action 105 | elif bot == 'acrobot_2link': 106 | from acrobot_2link import evolveFns,armXY,armAngles 107 | N = 4 # 2-link arm 108 | div_torq = 2. 109 | max_dq = np.array((4*np.pi,9*np.pi)) # with zero friction (B matrix) 110 | torques = np.array([(0.,div_torq),(0.,0.),(0.,-div_torq)]) 111 | len_actions = 3 112 | setpointX = 1. 113 | setpointY = -1. 114 | acrobot = True 115 | robotdt = 0.05 # evolve with this time step 116 | animdt = 0.2 # time step for an action 117 | 118 | Tmax = 50000. 119 | robotdt_steps = int(Tmax/robotdt) 120 | robtrange = np.arange(0,Tmax,robotdt) 121 | animdt_steps = int(Tmax/animdt) 122 | robotdt_per_animdt = int(animdt/robotdt) # must be an integral multiple 123 | 124 | qzero = np.zeros(N//2) # angles and angvelocities at start are subtracted below 125 | dqzero = np.zeros(N//2) # start from zero, fully downward position initially 126 | 127 | 128 | def evolve_animdt(q,dq,torquet,oldtorquet): 129 | for i in range(robotdt_per_animdt): 130 | # linearly interpolate between previous torque and current torque 131 | torque = oldtorquet + i/float(robotdt_per_animdt)*(torquet-oldtorquet) 132 | qdot,dqdot = evolveFns(q,dq,torque,dt=robotdt) 133 | q += qdot*robotdt 134 | dq += dqdot*robotdt 135 | return q,dq 136 | 137 | num_tiles = 10 138 | max_q = 2*np.pi 139 | div_q = max_q/num_tiles 140 | div_dq = 2*max_dq/num_tiles # abs(angular velocities) must be less than max_dq 141 | def get_robot_stateaction(angles,velocities,action): 142 | return tuple( np.append( (((angles+max_q/2.)%max_q)//div_q).astype(int), 143 | ((velocities+max_dq/2.)//div_dq).astype(int) ) ) 144 | # return tuple to be used as indices 145 | # negatives not allowed, hence add constants 146 | 147 | def doRL(): 148 | Niter = 5000 149 | Q = np.zeros(shape=np.append([num_tiles]*N,len_actions)) 150 | elig = np.zeros(shape=Q.shape) 151 | timetaken = np.zeros(Niter,dtype=int) 152 | epsilon = 0. # epsilon-greedy policy 153 | gamma = 1 # no discounting 154 | lambdaC = 0.9 155 | alpha = 0.2/48. 156 | torqueArray = np.zeros(shape=(int(Tmax/animdt),N//2)) 157 | for i in range(Niter): 158 | q = np.copy(qzero) # must copy, else pointer is used 159 | dq = np.copy(dqzero) 160 | action = action0 161 | it = 0 # time step index 162 | idxs = get_robot_stateaction(q,dq,action) 163 | stateaction = tuple(np.append(idxs,action)) 164 | torqueArray[0,:] = torques[action] 165 | while True: 166 | ## break, i.e. this iteration is over, if target is reached 167 | if task=='swing2' and 'arm_2link' in bot: 168 | # hip and endpoint of acrobot should go beyond a target point 169 | if -armXY(q)[0] > setpointY and armXY(q)[1] > setpointX and \ 170 | -armXY(q)[-2] > setpointY and armXY(q)[-1] > setpointX: break # -ve of first x is height of middle point 171 | else: 172 | #if -armXY(q)[-2] > 0.2 and armXY(q)[-1] > 0.2: break # -ve of last x is height of end point 173 | if -armXY(q)[-2] > setpointY and armXY(q)[-1] > setpointX: break # -ve of last x is height of end point 174 | 175 | ## store previous state-action value, and update eligibility for that state-action 176 | Qold = Q[stateaction] 177 | elig[stateaction] += 1. 178 | actionold = action 179 | ## choose next action 180 | idxs = get_robot_stateaction(q,dq,action) 181 | #print q,dq,idxs 182 | action_values = Q[idxs] 183 | if np.random.uniform() < epsilon: 184 | action = int(np.random.uniform()*len_actions) 185 | else: 186 | actions = np.where(action_values == np.amax(action_values))[0] 187 | action = actions[ np.random.permutation(len(actions))[0] ] 188 | # choose one action randomly out of those with same Q values 189 | 190 | ## take action, evolve bot 191 | q,dq = evolve_animdt(q,dq,torques[action],torques[actionold]) 192 | 193 | ## get reward 194 | #reward = -armXY(q)[-2] # - last x is height of end point 195 | reward = -1 # basically no reward, except to exit loop when height is reached 196 | 197 | ## update variables 198 | stateaction = tuple(np.append(idxs,action)) 199 | delta = reward + gamma*Q[stateaction] - Qold 200 | Q += alpha*delta*elig 201 | elig *= gamma*lambdaC 202 | it += 1 203 | torqueArray[it,:] = torques[action] 204 | 205 | print('Finished iteration',i,'in time',it*animdt,'s') 206 | timetaken[i] = it 207 | 208 | return timetaken,torqueArray 209 | 210 | import pickle 211 | if loadOld: 212 | timetaken,torqueArray = pickle.load( open( bot+"_"+task+"_data.pickle", "rb" ) ) 213 | else: 214 | timetaken,torqueArray = doRL() # learning input torque over time using RL 215 | pickle.dump( (timetaken,torqueArray), open( bot+"_"+task+"_data.pickle", "wb" ) ) 216 | 217 | plt.figure() 218 | plt.plot(timetaken) 219 | 220 | print('simulating + animating arm') 221 | # animation reference: http://matplotlib.org/1.4.1/examples/animation/double_pendulum_animated.html 222 | fig = plt.figure(facecolor='w',figsize=(3, 3),dpi=300) # default figsize=(8,6) 223 | # VERY IMPORTANT, xlim-ylim must be a square 224 | # as must be figsize above, else aspect ratio of arm movement is spoilt 225 | if acrobot: 226 | ax = fig.add_subplot(111, autoscale_on=False, xlim=(-2.,2.), ylim=(-2.5,1.5), clip_on=False) 227 | else: 228 | ax = fig.add_subplot(111, autoscale_on=False, xlim=(-0.65,0.65), ylim=(-0.65,0.65), clip_on=False) 229 | lineRef, = ax.plot([], [], 'o-r', lw=2, clip_on=False) 230 | linePred, = ax.plot([], [], 'o-b', lw=2, clip_on=False) 231 | time_text = ax.text(0.2, 0.78, '', transform=ax.transAxes, fontsize=label_fontsize) 232 | beautify_plot(ax,x0min=False,y0min=False,xticks=[],yticks=[],drawxaxis=False,drawyaxis=False) 233 | axes_labels(ax,'','$\longleftarrow$ gravity',xpad=-20) 234 | ax.text(0.45, 0.86, 'Acrobot',\ 235 | transform=fig.transFigure) 236 | 237 | def init(): 238 | lineRef.set_data([], []) 239 | linePred.set_data([], []) 240 | time_text.set_text('') 241 | return lineRef, linePred, time_text 242 | 243 | q = np.copy(qzero) # must copy, else pointer is used 244 | dq = np.copy(dqzero) 245 | def animate(i): 246 | global q,dq 247 | d,dq = evolve_animdt(q,dq,torqueArray[i+1],torqueArray[i]) 248 | if N==2: 249 | x1,y1 = armXY(q) 250 | lineRef.set_data([[0,y],[0,-x]]) # angle=0 is along gravity, so rotate axes by -90degrees 251 | else: 252 | x0,y0,x1,y1 = armXY(q) 253 | lineRef.set_data([[0,y0,y1],[0,-x0,-x1]]) # angle=0 is along gravity, so rotate axes by -90degrees 254 | time_text.set_text( 'time%.2f; X,Y=%.2f,%.2f'%((i+1)*animdt,y1,-x1) ) 255 | return lineRef, linePred, time_text 256 | 257 | # bug with blit=True with default tkAgg backend 258 | # see https://github.com/matplotlib/matplotlib/issues/4901/ 259 | # install python-qt4 via apt-get and set QT4Agg backend; as at top of this file 260 | anim = animation.FuncAnimation(fig, animate, 261 | init_func=init, frames=timetaken[-1], interval=0, blit=True, repeat=False) 262 | 263 | plt.show() 264 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # FOLLOW 2 | Feedback-based Online Local Learning Of Weights (FOLLOW) 3 | 4 | Code for the article: 5 | Predicting non-linear dynamics by stable local learning in a recurrent spiking neural network 6 | Aditya Gilra, Wulfram Gerstner, eLife, 6:e28295, 2017. 7 | [https://elifesciences.org/articles/28295](https://elifesciences.org/articles/28295) 8 | ( preprint at [arXiv:1702.06463](https://arxiv.org/abs/1702.06463) ). 9 | Source code home: [https://github.com/adityagilra/FOLLOW](https://github.com/adityagilra/FOLLOW) 10 | 11 | ---- 12 | ## Installing software: 13 | 14 | FOLLOW learning requires the use of heterogeneous spiking LIF neurons with pre-learned auto-encoder. The [Nengo simulator](https://www.nengo.ai/) (short for Neural Engineering Object), which implements the Neural Engineering Framework of Eliasmith and Anderson, 2004 is ideally suited for this. 15 | You can install Nengo by: 16 | `pip install nengo` 17 | 18 | (For the simulations in the paper, I used Nengo v2.4.0, but the code will also work with v2.5.0, but you'll need to set lower learning rate eta -- see the aside below.) 19 | Note: eta in the code is actually eta\*k of the eLife paper (cf. equations (8) and (10) in the paper), because the error term sent to the Nengo.PES learning rule on the ff and rec connections is without the k. Hence eta=2e-3 in the code corresponds to eta=2e-4 in the eLife paper corrected version 3 (Table 1). 20 | 21 | Currently, the scripts are configured to use Nengo's default CPU backend. This is slow! I **strongly** recommend to use the GPU backend which is about 25 times faster! 22 | 23 | For speed, I use the GPU back-end of the Nengo simulator [nengo_ocl](https://github.com/nengo/nengo_ocl). For the FOLLOW simulations, I found the GPU backend to be **~25 times faster** than the CPU backend. For good learning, I required about 10,000s of training the network which even on the GPU backend took about 24 hours for the van der Pol oscillator example (3000 feedforward and 3000 recurrently connected neurons). Thus, I strongly recommend using the GPU backend, but this might require a dedicated graphics card on a server -- on a laptop like mine, the GPU doesn't have enough memory. 24 | In the main python scripts used below, you'll have to set the parameter OCL to True to use the OpenCL (OCL) based GPU backend of Nengo: 25 | `OCL = True#False # use nengo_ocl or nengo to simulate` 26 | You need to install OpenCL libraries for the GPU you have (NVidia/AMD), and then pyopencl (see [nengo_ocl page](https://github.com/nengo/nengo_ocl) for details about all these), and finally nengo_ocl: 27 | `pip install nengo_ocl` 28 | 29 | ---- 30 | ### An aside concerning some minor issues with different versions on Nengo. 31 | 32 | For the [paper](https://arxiv.org/abs/1702.06463), I have used Nengo version 2.4.0 with nengo_ocl git commit of Apr 11 2017 with identifier: 6d275686b1e771975fe7d6ddd44ae4b778ce0ce6 33 | 34 | To install the old version of Nengo: 35 | `pip uninstall nengo` 36 | `pip install nengo==2.4.0` 37 | But latest nengo_ocl does not work with nengo v2.4.0, so you need an older version of that too: 38 | `pip uninstall nengo_ocl` 39 | `git clone https://github.com/nengo/nengo_ocl.git` 40 | `cd nengo_ocl` 41 | `git checkout 6d275686b1e771975fe7d6ddd44ae4b778ce0ce6` 42 | Be sure to set the PYTHONPATH to include above nengo_ocl directory after this. 43 | 44 | All the code also runs with the newer version 2.5.0 of Nengo, but from version 2.5.0 onwards, the learning rate used currently will be too high for v2.5.0 leading to large oscillations in output from the start. Set eta=1e-4 instead of 2e-3. Further, there will be a huge variability in instantaneous rates of firing. These two differences arise because the way the neural gains are implemented has changed. See the details here: 45 | [https://github.com/nengo/nengo/pull/1330](https://github.com/nengo/nengo/pull/1330) 46 | Drasmuss says: """nengo.Connection(x, ens.neurons) was applying the neural gains before the synapse (synapse(x*gains)), whereas nengo.Connection(x, ens) was applying the gains after the synapse (synapse(x)*gains). This changes it so that the implementation is consistent in both cases (I went with the latter formulation).""" 47 | Drasmuss also mentions another change (point 2), but in the discussion below, he says he reverted it back. 48 | 49 | So in v2.4.0, current in a neuron (with encoder $e_{i\alpha}$, gain $\nu_i$ and bias $b_i$) in our recurrent network is (note that $\nu_i$ only multiplies the encoders term, not all the terms, because the first two terms are `Connection`s from `Ensemble.neurons` to `Ensemble.neurons`, rather than from `Ensemble` to `Ensemble`): 50 | 51 | $J_i = \sum_l w^{\textnormal{ff}}_{il} (S^{\textnormal{ff}}_l*\kappa)(t) + 52 | \sum_j w_{ij} (S_j*\kappa)(t) + 53 | \nu_i \sum_\alpha k e_{i\alpha} (\epsilon_\alpha*\kappa)(t) 54 | + b_i,$ 55 | but in v2.5.0, and perhaps in future versions too, the gain $\nu_i$ multiplies all the three terms (not bias of course). During learning, since the gain multiplies the weights too, in the later version, the effective learning rate becomes different and needs to be adjusted between the two versions. After learning, this results in some neurons firing at very high instantaneous rates in the later version, thus the mean firing rates of neurons using Nengo v2.5.0 is higher than when using v2.4.0, with all other parameters constant. 56 | 57 | You can even just use constant gain as I did for Figure 2 in the paper, to obtain lower variability in rates. 58 | 59 | ----- 60 | 61 | ## Running simulations 62 | 63 | Here, I only document how to run the most basic simulations for the van der Pol (Figure 2's higher firing rate version i.e. Fig. 2-figure supplement 1 - panels Ai, Bi, Ci) and the arm (Fig. 4 - panels Ai, Bi, Ci) examples. Simulations for other figures in the paper require various settings, and different learning and test runs. 64 | 65 | ### Learning a forward model of the van der Pol oscillator: 66 | Currently only 40 s of simulation is set in the script `input_ff_rec_transform_nengo_ocl.py`. Even this takes about 3 hours on an i7 CPU on my laptop, but around 3 minutes on an NVidia Titan X GPU using nengo_ocl. So use nengo_ocl and set `OCL = True`, or try with less number of neurons `Nexc`, currently 3000 feedforward and 3000 recurrently connected neurons (but the approximation of the system will be poor with lesser number of neurons). 67 | Modify simulation time by changing Tmax parameter to 10000 (seconds) to get data for Figure 2-figure supplement 1 panels Ai, Bi, Ci. For first 4 s (Tperiod = 4 s), feedback is off, then feedback and learning are turned on. For the last 16 s (4*Tperiod), feedback and learning are turned off for testing after learning. I use `nohup` to run the process in the background, so that it stays running even if I log out of the server. Use `cat nohup0.out` or `less nohup0.out` to check how long the simulation has run (takes some time to set up first, before it shows the progress bar of the simulation). 68 | `nohup python input_ff_rec_transform_nengo_ocl.py &> nohup0.out &` 69 | 70 | The script will pop up plots for the command input $u$, error $\epsilon$, network predicted state $\hat{x}$, reference state $x$ and squared error, all as a function of time. 71 | The script will also save the data into 4 files with one of 4 suffixes as below (note if not using GPU, _ocl will not be present in the name): 72 | "data/ff_ocl_Nexc3000_seeds2344_weightErrorCutoff0.0_nodeerr_learn_rec_nocopycat_func_vanderPol_trials_seed2by50.0amplVaryHeightsScaled_40.0s_.shelve" 73 | ...start and ...end save the first 5 Tperiods and last 5 Tperiods of the simulation respectively, ...currentweights saves feedforward and recurrent weights at 20 time-points during the simulation, ...endweights saves the feedforward and recurrent weights at the end of simulation (learned weights). 74 | To later display the saved data, run: 75 | `python input_rec_transform_nengo_plot.py data/ff_ocl_Nexc3000_seeds2344_weightErrorCutoff0.0_nodeerr_learn_rec_nocopycat_func_vanderPol_trials_seed2by50.0amplVaryHeightsScaled_40.0s` 76 | 77 | Testing on structured input as in panels Fig. 2-figure supplement 1 Aii, Bii - requires further change of parameters to load the weights of the learned network, and run with a different input protocol. In particular after the above learning, you need to change parameters as below and re-run the above simulation for a test duration. Set continueTmax for however long you ran the above learning simulation, here 40 s as above. Then set Tmax to how long you want to test, typically just 40 s. 78 | ```testLearned = True#False # whether to test the learning, uses weights from continueLearning, but doesn't save again. 79 | seedRin = 3#2 80 | inputType = 'rampLeaveRampHeights' 81 | #inputType = 'amplVaryHeightsScaled' 82 | Tmax = 40. # second 83 | continueTmax = 40. # if continueLearning or testLearned, 84 | # then start with weights from continueTmax 85 | # and run the learning/testing for Tmax 86 | ``` 87 | Again, run the simulation 88 | `nohup python input_ff_rec_transform_nengo_ocl.py &> nohup0.out &` 89 | The script generates plots for test input, and data files of the name prefix as below (note if not using GPU, _ocl will not be present in the name), which you can then plot as above. 90 | "data/ff_ocl_Nexc3000_seeds2344_weightErrorCutoff0.0_nodeerr_learn_rec_nocopycat_func_vanderPol_trials_seed2by50.0amplVaryHeightsScaled_testFrom40.0_seed3by50.0rampLeaveRampHeights_40.0s" 91 | 92 | Of course you need at least 1000 s of learning to see some resemblance to the reference in the test, and 5000 to 10000 s to see good learning. To make learning faster, first run learning for 500 s, then set the learning rate to 20 times the current 2e-3 i.e. to 4e-2 and then run for 500 s more by setting `continueLearning = True`, `continueTmax = 500`, `Tmax=500`, and `seedRin = 3`. Then you can run the test as above, with `continueTmax = 1000`. 93 | 94 | ### Learning a forward model of the arm: 95 | The sequence of simulations for learning and testing, and the parameter names and data filenames for the arm learning (5000 feedforward and 5000 recurrent neurons) are very similar to the above van der Pol example. However, the simulation script is different (here `input_ff_rec_robot_nengo_directu_ocl.py`), though the plotting script is the same. 96 | Currently only 10 s of simulation is set in the script `input_ff_rec_robot_nengo_directu_ocl.py`. Modify it by changing Tmax parameter to 15000 (seconds) to get data for Figure 4 Ai, Bi, Ci. For first 1 s (Tperiod), feedback is off, then feedback and learning are turned on. For the last 4 s (4*Tperiod), feedback and learning are turned off for testing after learning. I use `nohup` to run the process in the background, so that it stays running even if I log out of the server. 97 | `nohup python input_ff_rec_robot_nengo_directu_ocl.py &> nohup1.out &` 98 | 99 | The script imports "sim_robot.py" and "arm*.py" for simulating the reference arm dynamics. The file saves data with name as below (note if not using GPU, _ocl will not be present in the name), here there is no ...currentweights file as it would be huge. 100 | "data/ff_rec_ocl_Nexc5000_norefinptau_directu_seeds2345_weightErrorCutoff0.0_nodeerr_learn_rec_nocopycat_func_robot2_todorov_gravity_seed2by0.3amplVaryHeights_10.0s_.shelve" 101 | 102 | Testing proceeds as for the van der Pol oscillator example. Change parameters as below, and rerun the simulation command as above, to get test plots and data files, set continueTmax to however long you ran the learning. 103 | ```testLearned = True#False # whether to test the learning, uses weights from continueLearning, but doesn't save again. 104 | seedRin = 3#2 105 | Tmax = 10. # second - how long to run the simulation 106 | continueTmax = 10. # if continueLearning or testLearned, then start with weights from continueTmax 107 | ``` 108 | This will test on random input as during training. To test on the acrobot swinging, first run `python RL_acrobot.py`, then modify parameters (apart from the above ones already modified for testing) in the simulation script file: 109 | ```#inputType = 'amplVaryHeights' 110 | inputType = 'RLSwing' 111 | ``` 112 | Once this completes, it'll generate a file name "arm_2link_swing_data.pickle" that contains the command input that makes the reference arm swing to reach a target (uses reinforcement learning to figure out command input). To re-run the animation for this arm data, just set `loadOld = True` and `#loadOld = False` (comment out), and re-run `python RL_acrobot.py`. 113 | Then run the simulation script for 10 s as above to generate the test data plots and files. 114 | 115 | ### Other figures 116 | I ran simulations with various different settings of parameters, and collated a number of data files to plot any given figure using the script `input_rec_transform_nengo_plot_figs.py`. You could take a look at the names of the data files being plotted in that script and that gives a clue to what parameters to change in the above simulation script files. If that doesn't help contact me! 117 | 118 | Bon FOLLOW-ing!!! 119 | -------------------------------------------------------------------------------- /rate_evolve.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Linear response with integral equations 3 | # (c) May 2015 Aditya Gilra, EPFL. 4 | 5 | """ 6 | rate units evolution with Hennequin or EI weight matrix 7 | written by Aditya Gilra (c) May 2015. 8 | """ 9 | 10 | from pylab import * 11 | import pickle 12 | from scipy.integrate import odeint 13 | from scipy.linalg import schur 14 | from scipy.interpolate import interp1d 15 | 16 | import warnings 17 | warnings.filterwarnings('error') # to catch complex to real conversion warning 18 | 19 | ################## Initialization and loading the correct matrix ################## 20 | 21 | seedR = 999 # seed for the W file is in the function 22 | # this is just for reproducibility 23 | seed(seedR) 24 | np.random.seed(seedR) 25 | 26 | tau = 0.02 # second 27 | rampT = 0.1 # second 28 | Tmax = rampT+1.0 # second 29 | 30 | #init_vec_idx = -1 31 | init_vec_idx = 0 # first / largest response vector 32 | 33 | #evolve = 'EI' # eigenvalue evolution 34 | #evolve = 'Q' # Hennequin et al 2014 35 | evolve = 'fixedW' # Schaub et al 2015 / 2D oscillator 36 | #evolve = None # no recurrent connections 37 | 38 | evolve_dirn = 'arb' # arbitrary normalized initial direction 39 | #evolve_dirn = '' # along a0, i.e. eigvec of response energy matrix Q 40 | #evolve_dirn = 'eigW' # along eigvec of W 41 | #evolve_dirn = 'schurW' # along schur mode of W 42 | 43 | evolveType = 'ODE' 44 | #evolveType = 'linizeExpMomentKernel' 45 | 46 | #normalizeKernel = True # else response can blow up 47 | 48 | def loadW(evolve): 49 | if evolve is None: 50 | M =1#10 51 | W = zeros((2*M,2*M)) 52 | Winit = W 53 | lambdas = zeros(2*M) 54 | a0s = W 55 | desc_str = "empty W" 56 | elif evolve == 'eye': 57 | M =10 58 | W = diag([1]*M+[0]*M) # only exc neurons are assemblies 59 | Winit = copy(W) 60 | lambdas,a0s = eig(W) 61 | desc_str = "identity" 62 | elif evolve == 'fixedW': 63 | #M = 2 64 | ## Schaub et al 2015 eqns 2,3 network 65 | #s=0.8; epsilon=0.2; w=s+epsilon; k=1.1; 66 | #W = array( [ [s,epsilon,-k*w,0],[epsilon,s,-k*w,0],\ 67 | # [w/2.,w/2.,-k*w,0],[0,0,0,0] ] ) 68 | # # extra useless variable as we require N=2*M 69 | 70 | ## simple oscillator 71 | #M=1 72 | #taudyn = 0.3 # second 73 | #W = array( [[0,-1],[1,0]] )/taudyn*tau + eye(2*M) 74 | # # So that (W-I)/tau = [[0,-1],[1,0]]/taudyn 75 | 76 | # simple decaying oscillator 77 | M=1 78 | taudyn = 0.05 # second 79 | decay_fac = -0.2 # effective decay_tau = taudyn/decay_fac 80 | W = array( [[decay_fac,-1],[1,decay_fac]] )/taudyn*tau + eye(2*M) 81 | # So that (W-I)/tau = [[decay_fac,-1],[1,decay_fac]]/taudyn 82 | 83 | ## non-normal matrix from Chap 1 pg 18 of Hennequin thesis and Murphy and Miller 2009 84 | #M=1 85 | #W = array( [[150,-220],[190,-270]] )/10.*tau + eye(2*M) 86 | # # (W-I)/tau is used finally 87 | 88 | Winit = copy(W) 89 | lambdas,a0s = eig(W) 90 | desc_str = "identity" 91 | elif evolve == 'EI': 92 | filestart = 'eigenW' 93 | M = 10 # number of E neurons = number of I neurons 94 | rndseed = 108 95 | WisNormal = False # decide if normal or non-normal W is to be loaded 96 | fn = filestart+str(rndseed)+"M"+str(M)+\ 97 | 'normal'+str(WisNormal)+".pickle", 98 | W,lambdas,a0s = pickle.load( open( fn,"rb" ) ) 99 | print("Read ",fn) 100 | Winit = W 101 | if WisNormal: 102 | desc_str = 'real normal W' 103 | else: 104 | desc_str = 'real non-normal (EI) stable W' 105 | else: 106 | filestart = 'stabW' 107 | M = 3#20 # number of E neurons = number of I neurons 108 | rndseed = 100 109 | EI_separate = True 110 | fn = filestart+str(rndseed)+"M"+str(M)+\ 111 | ('_EI' if EI_separate else '')+".pickle" 112 | W,Winit,lambdas,a0s = pickle.load( open( fn,"rb" ) ) 113 | print("Read ",fn) 114 | desc_str = 'stabilized SOC (EI)' 115 | return M,W,Winit,lambdas,a0s,desc_str 116 | 117 | ############### Calculate relevant modes of the relevant matrix ############ 118 | def get_relevant_modes(evolve_dirn,W,lambdas,a0s): 119 | if evolve_dirn is None: 120 | v = zeros(len(lambdas)) 121 | w = zeros(W.shape) 122 | dir_str = 'no direction (spontaneous)' 123 | elif evolve_dirn == '': 124 | # a0 and lambdas contain either eigvals/vecs of Q if evolve='Q' 125 | # of the eigvals/Schur-modes of W if evolve='EI' 126 | v = lambdas 127 | w = a0s 128 | dir_str = 'response direction of Q' 129 | elif evolve_dirn == 'arb': 130 | v = lambdas # unused later for arb 131 | w = a0s # not used later for arb 132 | dir_str = 'arbitrary direction' 133 | elif evolve_dirn == 'schurW': 134 | v,w = schur(W,output='complex') # output="real" will give 2x2 blocks 135 | # on diagonal for complex eigenvalues 136 | # W = Z T Z^H 137 | v = diag(v) 138 | dir_str = 'schur mode of W' 139 | elif evolve_dirn == 'eigW': 140 | v,w = eig(W) 141 | dir_str = 'eigen mode of W' 142 | else: 143 | print("error: provide a valid evolve_dirn") 144 | sys.exit(1) 145 | return v,w,dir_str 146 | 147 | ################ Take care of real vs complex modes ################### 148 | def get_stim_dirn(evolve_dirn,v,w,init_vec_idx,W): 149 | N = len(v) 150 | if evolve_dirn is None: 151 | y0 = zeros(len(v)) 152 | y01 = zeros(len(v)) 153 | y02 = zeros(len(v)) 154 | elif evolve_dirn != 'arb': 155 | # stimulate along a direction given v,w 156 | sortidxs = argsort(v) # sorts by real part, then imag part 157 | sortidxs = sortidxs[::-1] # highest real part first 158 | sortidx = sortidxs[init_vec_idx] 159 | # sorting full eigenvals/vecs doesn't work 160 | # the conjugate pairs are not kept together 161 | #vsort = v[sortidxs] # eigenvalues of W 162 | #wsort = w[:,sortidxs] # directions for eigen response 163 | y0full = w[:,sortidx] 164 | # the initial input vector 165 | # eigenvector of Q or W 166 | # note eigvec can be complex even if eigval is real 167 | y0 = real(y0full) # only the real part is used as initial condition 168 | # if cc pair of eigenvalues, 169 | # real(eigvec) stim gives exp()*cos() response 170 | # if single real eigenvalue, 171 | # real(eigvec) stim gives exp() response 172 | # CAREFUL: For arrays never do y0 /= norm(y0). 173 | # It changes the array w from which y0 was indexed!!!! 174 | y0 = y0 / norm(y0) # ensure norm 1; taking real() changes norm 175 | vused = v[sortidx] # corresponding eigenval 176 | if abs(imag(v[sortidx])) < 1e-10: # real eigenvalue 177 | y01 = y0/2. 178 | y02 = y0/2. 179 | print("Real eigenvalue", vused) 180 | if evolve_dirn != '': 181 | print("Confirm decomposition? norm( dot(w,diag(v)) - dot(W,w) ) =", \ 182 | norm( dot(w,diag(v)) - dot(W,w) )) 183 | print("Confirm eigenvector? norm( dot(W,y0) - vused*y0 ) =", \ 184 | norm( vused*y0full - dot(W,y0full) )) 185 | else: # complex eigenvalue pair 186 | y01 = w[:,sortidx] 187 | sortidxcc = where(abs(v-conj(vused))<1e-10)[0][0] 188 | y02 = w[:,sortidxcc] 189 | # y01 and y02 need not be orthogonal even if they belong to cc pairs. 190 | print("Dot product of eigenvectors corresponding to cc pair =",\ 191 | dot(y01,conj(transpose(y02)))) 192 | print("Complex eigenvalues (confirm cc pair)", vused, v[sortidxcc]) 193 | if abs( vused - conj(v[sortidxcc]) ) > 1e-10: 194 | print("error in sort order.") 195 | sys.exit(1) 196 | if evolve_dirn != '': 197 | print("Confirm decomposition? norm( dot(w,diag(v)) - dot(W,w) ) =", \ 198 | norm( dot(w,diag(v)) - dot(W,w) )) 199 | print("Confirm eigenvector? norm( dot(W,y01) - vused*y01 ) =", \ 200 | norm( vused*y01 - dot(W,y01) )) 201 | print("Unitary eigenmatrix P? norm( dot(transpose(conj(P)),P) - I ) =",\ 202 | norm( dot(w,transpose(conj(w)))-eye(N) )) 203 | else: # arbitrary evolution 204 | y0 = uniform(-1,1,N) # random initial direction 205 | #y0 = array([1,0]) # for non-normal 2D fixedW 206 | y0 = y0/norm(y0) # normalized 207 | y01 = y0/2. 208 | y02 = y0/2. 209 | return y0,y01,y02 210 | 211 | if __name__ == "__main__": 212 | 213 | M,W,Winit,lambdas,a0s,desc_str = loadW(evolve) 214 | v,w,dir_str = get_relevant_modes(evolve_dirn,W,lambdas,a0s) 215 | y0,y01,y02 = get_stim_dirn(evolve_dirn,v,w,init_vec_idx,W) 216 | print("Normality check for real W. Frobenius norm of (W^T*W - W*W^T) =",\ 217 | norm(dot(transpose(W),W)-dot(W,transpose(W)))) 218 | N = len(v) 219 | I = eye(N) 220 | zerosN = zeros(N)+1e-10 221 | 222 | ################ Time evolution ############### 223 | 224 | dt = 0.001 225 | trange = arange(0.0,Tmax,dt) 226 | B = y0 - dot(W,y0) 227 | 228 | if evolveType == 'ODE': 229 | def matevolve(y,t): 230 | if t=0)*exp(-t/tau) 246 | kernel = kernelsyntildeInterp(arange(0.0,tarray[-1],dt)) 247 | kerlen = len(kernel) 248 | #y = repeat(transpose([y0]),kerlen+1,axis=1) 249 | # 200 ms of initial y0 250 | # integral approach so not just last time point, 251 | # but kernel length/time-scale of history is need. 252 | y = append(zeros(shape=(N,kerlen)),transpose([y0]),axis=1) 253 | revkernel = kernel[::-1] 254 | for t in trange: 255 | ynext = dot(W-I,sum(y[:,-kerlen:]*revkernel,axis=1)*dt) 256 | y = append(y,transpose([ynext]),axis=1) 257 | 258 | y = transpose(y[:,-len(trange):]) 259 | 260 | ############### Analysis of response ################# 261 | 262 | y01dagger = conj(transpose(y01)) 263 | y02dagger = conj(transpose(y02)) 264 | y_y01 = dot(y,y01dagger) # dot-product of complex vectors 265 | y_y02 = dot(y,y02dagger) 266 | yeigen = outer(y_y01,y01) + outer(y_y02,y02) 267 | imyeigen = sum(abs(imag(yeigen))) 268 | print("yeigen should be real, sum(abs(imag(yeigen))) = ", imyeigen) 269 | if imyeigen > 1e-10: # ideally number of time points 270 | # should also be factored in 271 | print("Check yeigen") 272 | sys.exit(1) 273 | yeigen = real(yeigen) 274 | ybgnd = y - yeigen 275 | 276 | ############### Plotting ################# 277 | 278 | fig = figure(dpi=100,facecolor='white') 279 | fig.suptitle(desc_str+'; Init condn along '+dir_str,fontsize=14) 280 | ax = fig.add_subplot(221) 281 | ax.plot(trange,y) 282 | ylabel('ampl (arb)') 283 | xlabel('time (s)') 284 | ax.set_title('response vs time') 285 | 286 | normy = [ norm(y[i,:]) + 1e-12 for i in range(len(trange)) ] 287 | 288 | # normalized overlap with initial direction 289 | ax = fig.add_subplot(222) 290 | plot(trange,ybgnd) 291 | plot(trange,abs(y_y01)/normy,'k',linewidth=3.0) 292 | plot(trange,abs(y_y02)/normy,'k',linewidth=3.0) 293 | xlabel('time (s)') 294 | ylabel('ampl (arb)') 295 | ax.set_title('norm-ed overlap on 2 init dirns. & residual') 296 | 297 | ax = fig.add_subplot(223) 298 | plot(trange,yeigen) 299 | xlabel('time (s)') 300 | ylabel('ampl (arb)') 301 | ax.set_title('response along init dirns.') 302 | 303 | ax = fig.add_subplot(224) 304 | if evolve=='Q': 305 | vplot,wplot = eig(Winit) 306 | scatter(real(vplot),imag(vplot),color='grey') 307 | vplot,wplot = eig(W) 308 | scatter(real(vplot),imag(vplot),color='b') 309 | xlabel('Re($\lambda$)') 310 | ylabel('Im($\lambda$)') 311 | ax.set_title('Weight matrix eigenvals') 312 | 313 | fig.tight_layout() 314 | fig.subplots_adjust(top=0.9) 315 | 316 | fig.savefig('rate_evolve'+evolve+evolve_dirn+'.png') 317 | 318 | figure(facecolor='w') 319 | plot(trange,normy/norm(y[int(rampT/dt)])) 320 | ylabel('norm(activity) / norm(init)') 321 | xlabel('time (s)') 322 | title('normed response vs time') 323 | 324 | show() 325 | -------------------------------------------------------------------------------- /plot_utils.py: -------------------------------------------------------------------------------- 1 | import string 2 | #import matplotlib 3 | #matplotlib.use('Agg') 4 | #matplotlib.use('GTK') 5 | from pylab import * 6 | from matplotlib import collections 7 | from mpl_toolkits.axes_grid.inset_locator import inset_axes 8 | 9 | ## choose figure or poster defaults 10 | #fig_defaults = 'poster' # poster defaults 11 | #fig_defaults = 'presentation' # presentation defaults 12 | fig_defaults = 'paper' # paper figure defaults 13 | 14 | if fig_defaults == 'paper': 15 | ####### paper figure defaults 16 | label_fontsize = 8 # pt 17 | plot_linewidth = 0.5 # pt 18 | linewidth = 1.0#0.5 19 | axes_linewidth = 0.5 20 | marker_size = 3.0 # markersize=<...> 21 | cap_size = 2.0 # for errorbar caps, capsize=<...> 22 | columnwidth = 85/25.4 # inches 23 | twocolumnwidth = 174/25.4 # inches 24 | linfig_height = columnwidth*2.0/3.0 25 | fig_dpi = 300 26 | elif fig_defaults == 'poster': 27 | ####### poster defaults 28 | label_fontsize = 12 # pt 29 | plot_linewidth = 1.0 # pt 30 | linewidth = 1.0 31 | axes_linewidth = 1.0 32 | marker_size = 3.0 33 | cap_size = 2.0 # for errorbar caps 34 | columnwidth = 4 # inches 35 | linfig_height = columnwidth*2.0/3.0 36 | else: 37 | ####### presentation defaults for screenshot 38 | label_fontsize = 20 # pt 39 | plot_linewidth = 0.5 # pt 40 | linewidth = 1.0#0.5 41 | axes_linewidth = 0.5 42 | marker_size = 3.0 # markersize=<...> 43 | cap_size = 2.0 # for errorbar caps, capsize=<...> 44 | columnwidth = 85/25.4 # inches 45 | twocolumnwidth = 174/25.4 # inches 46 | linfig_height = columnwidth*2.0/3.0 47 | fig_dpi = 300 48 | 49 | 50 | def axes_off(ax,x=True,y=True,xlines=False,ylines=False): 51 | ''' True is to turn things off, False to keep them on! 52 | x,y are for ticklabels, xlines,ylines are for ticks''' 53 | if x: 54 | for xlabel_i in ax.get_xticklabels(): 55 | xlabel_i.set_visible(False) 56 | xlabel_i.set_fontsize(0.0) 57 | if y: 58 | for xlabel_i in ax.get_yticklabels(): 59 | xlabel_i.set_fontsize(0.0) 60 | xlabel_i.set_visible(False) 61 | if xlines: 62 | for tick in ax.get_xticklines(): 63 | tick.set_visible(False) 64 | if ylines: 65 | for tick in ax.get_yticklines(): 66 | tick.set_visible(False) 67 | 68 | def set_tick_widths(ax,tick_width): 69 | for tick in ax.xaxis.get_major_ticks(): 70 | tick.tick1line.set_markeredgewidth(tick_width) 71 | tick.tick2line.set_markeredgewidth(tick_width) 72 | for tick in ax.xaxis.get_minor_ticks(): 73 | tick.tick1line.set_markeredgewidth(tick_width) 74 | tick.tick2line.set_markeredgewidth(tick_width) 75 | for tick in ax.yaxis.get_major_ticks(): 76 | tick.tick1line.set_markeredgewidth(tick_width) 77 | tick.tick2line.set_markeredgewidth(tick_width) 78 | for tick in ax.yaxis.get_minor_ticks(): 79 | tick.tick1line.set_markeredgewidth(tick_width) 80 | tick.tick2line.set_markeredgewidth(tick_width) 81 | 82 | def axes_labels(ax,xtext,ytext,adjustpos=False,fontsize=label_fontsize,xpad=None,ypad=None): 83 | ax.set_xlabel(xtext,fontsize=fontsize,labelpad=xpad) 84 | # increase xticks text sizes 85 | for label in ax.get_xticklabels(): 86 | label.set_fontsize(fontsize) 87 | ax.set_ylabel(ytext,fontsize=fontsize,labelpad=ypad) 88 | # increase yticks text sizes 89 | for label in ax.get_yticklabels(): 90 | label.set_fontsize(fontsize) 91 | if adjustpos: 92 | ## [left,bottom,width,height] 93 | ax.set_position([0.135,0.125,0.84,0.75]) 94 | set_tick_widths(ax,axes_linewidth) 95 | 96 | def biglegend(legendlocation='upper right',ax=None,fontsize=label_fontsize, **kwargs): 97 | if ax is not None: 98 | leg=ax.legend(loc=legendlocation, **kwargs) 99 | else: 100 | leg=legend(loc=legendlocation, **kwargs) 101 | # increase legend text sizes 102 | for t in leg.get_texts(): 103 | t.set_fontsize(fontsize) 104 | 105 | def beautify_plot(ax,x0min=True,y0min=True, 106 | xticksposn='bottom',yticksposn='left',xticks=None,yticks=None, 107 | drawxaxis=True,drawyaxis=True): 108 | """ 109 | x0min,y0min control whether to set min of axis at 0. 110 | xticksposn,yticksposn governs whether ticks are at 111 | 'both', 'top', 'bottom', 'left', 'right', or 'none'. 112 | xtickx/yticks is a list of ticks, else [min,0,max] for y and [min,max] for x is set. 113 | Due to rendering issues, 114 | axes do not overlap exactly with the ticks, dunno why. 115 | """ 116 | ax.get_yaxis().set_ticks_position(yticksposn) 117 | ax.get_xaxis().set_ticks_position(xticksposn) 118 | xmin, xmax = ax.get_xaxis().get_view_interval() 119 | ymin, ymax = ax.get_yaxis().get_view_interval() 120 | if x0min: xmin=0 121 | if y0min: ymin=0 122 | if xticks is None: ax.set_xticks([xmin,xmax]) 123 | else: ax.set_xticks(xticks) 124 | if yticks is None: ax.set_yticks([ymin,0,ymax]) 125 | else: ax.set_yticks(yticks) 126 | ### do not set width and color of axes by below method 127 | ### axhline and axvline are not influenced by spine below. 128 | #ax.axhline(linewidth=axes_linewidth, color="k") 129 | #ax.axvline(linewidth=axes_linewidth, color="k") 130 | ## spine method of hiding axes is cleaner, 131 | ## but alignment problem with ticks in TkAgg backend remains. 132 | for loc, spine in ax.spines.items(): # items() returns [(key,value),...] 133 | spine.set_linewidth(axes_linewidth) 134 | if loc == 'left' and not drawyaxis: 135 | spine.set_color('none') # don't draw spine 136 | elif loc == 'bottom' and not drawxaxis: 137 | spine.set_color('none') # don't draw spine 138 | elif loc in ['right','top']: 139 | spine.set_color('none') # don't draw spine 140 | ### alternate method of drawing axes, but for it, 141 | ### need to set frameon=False in add_subplot(), etc. 142 | #if drawxaxis: 143 | # ax.add_artist(Line2D((xmin, xmax), (ymin, ymin),\ 144 | # color='black', linewidth=axes_linewidth)) 145 | #if drawyaxis: 146 | # ax.add_artist(Line2D((xmin, xmin), (ymin, ymax),\ 147 | # color='black', linewidth=axes_linewidth)) 148 | ## axes_labels() sets sizes of tick labels too. 149 | axes_labels(ax,'','',adjustpos=False) 150 | ax.set_xlim(xmin,xmax) 151 | ax.set_ylim(ymin,ymax) 152 | return xmin,xmax,ymin,ymax 153 | 154 | def beautify_plot3d(ax,x0min=True,y0min=True, 155 | xticksposn='bottom',yticksposn='left',xticks=None,yticks=None,zticks=None, 156 | drawxaxis=True,drawyaxis=True): 157 | """ 158 | x0min,y0min control whether to set min of axis at 0. 159 | xticksposn,yticksposn governs whether ticks are at 160 | 'both', 'top', 'bottom', 'left', 'right', or 'none'. 161 | xtickx/yticks/zticks is a list of ticks, else [min,max] is set. 162 | Due to rendering issues, 163 | axes do not overlap exactly with the ticks, dunno why. 164 | """ 165 | xmin, xmax = ax.get_xlim() 166 | ymin, ymax = ax.get_ylim() 167 | zmin, zmax = ax.get_zlim() 168 | if x0min: xmin=0 169 | if y0min: ymin=0 170 | if xticks is None: ax.set_xticks([xmin,xmax]) 171 | else: ax.set_xticks(xticks) 172 | if yticks is None: ax.set_yticks([ymin,ymax]) 173 | else: ax.set_yticks(yticks) 174 | if zticks is None: ax.set_zticks([zmin,zmax]) 175 | else: ax.set_zticks(zticks) 176 | ### do not set width and color of axes by below method 177 | ### axhline and axvline are not influenced by spine below. 178 | #ax.axhline(linewidth=axes_linewidth, color="k") 179 | #ax.axvline(linewidth=axes_linewidth, color="k") 180 | ## spine method of hiding axes is cleaner, 181 | ## but alignment problem with ticks in TkAgg backend remains. 182 | for loc, spine in ax.spines.items(): # items() returns [(key,value),...] 183 | spine.set_linewidth(axes_linewidth) 184 | if loc == 'left' and not drawyaxis: 185 | spine.set_color('none') # don't draw spine 186 | elif loc == 'bottom' and not drawxaxis: 187 | spine.set_color('none') # don't draw spine 188 | elif loc in ['right','top']: 189 | spine.set_color('none') # don't draw spine 190 | ### alternate method of drawing axes, but for it, 191 | ### need to set frameon=False in add_subplot(), etc. 192 | #if drawxaxis: 193 | # ax.add_artist(Line2D((xmin, xmax), (ymin, ymin),\ 194 | # color='black', linewidth=axes_linewidth)) 195 | #if drawyaxis: 196 | # ax.add_artist(Line2D((xmin, xmin), (ymin, ymax),\ 197 | # color='black', linewidth=axes_linewidth)) 198 | ## axes_labels() sets sizes of tick labels too. 199 | axes_labels(ax,'','',adjustpos=False) 200 | # set zticks text sizes 201 | for label in ax.get_zticklabels(): 202 | label.set_fontsize(label_fontsize) 203 | ax.set_xlim(xmin,xmax) 204 | ax.set_ylim(ymin,ymax) 205 | ax.set_zlim(zmin,zmax) 206 | return xmin,xmax,ymin,ymax,zmin,zmax 207 | 208 | def fig_clip_off(fig): 209 | ## clipping off for all objects in this fig 210 | for o in fig.findobj(): 211 | o.set_clip_on(False) 212 | 213 | ## ------ 214 | ## from https://gist.github.com/dmeliza/3251476#file-scalebars-py 215 | 216 | # Adapted from mpl_toolkits.axes_grid2 217 | # LICENSE: Python Software Foundation (http://docs.python.org/license.html) 218 | 219 | from matplotlib.offsetbox import AnchoredOffsetbox 220 | class AnchoredScaleBar(AnchoredOffsetbox): 221 | def __init__(self, transform, sizex=0, sizey=0, labelx=None, labely=None, loc=4, 222 | pad=0.1, borderpad=0.1, sep=2, prop=None, label_fontsize=label_fontsize, color='k', **kwargs): 223 | """ 224 | Draw a horizontal and/or vertical bar with the size in data coordinate 225 | of the give axes. A label will be drawn underneath (center-aligned). 226 | - transform : the coordinate frame (typically axes.transData) 227 | - sizex,sizey : width of x,y bar, in data units. 0 to omit 228 | - labelx,labely : labels for x,y bars; None to omit 229 | - loc : position in containing axes 230 | - pad, borderpad : padding, in fraction of the legend font size (or prop) 231 | - sep : separation between labels and bars in points. 232 | - **kwargs : additional arguments passed to base class constructor 233 | """ 234 | from matplotlib.patches import Rectangle 235 | from matplotlib.offsetbox import AuxTransformBox, VPacker, HPacker, TextArea, DrawingArea 236 | bars = AuxTransformBox(transform) 237 | if sizex: 238 | bars.add_artist(Rectangle((0,0), sizex, 0, fc="none", linewidth=axes_linewidth, color=color)) 239 | if sizey: 240 | bars.add_artist(Rectangle((0,0), 0, sizey, fc="none", linewidth=axes_linewidth, color=color)) 241 | 242 | if sizex and labelx: 243 | textareax = TextArea(labelx,minimumdescent=False,textprops=dict(size=label_fontsize,color=color)) 244 | bars = VPacker(children=[bars, textareax], align="center", pad=0, sep=sep) 245 | if sizey and labely: 246 | ## VPack a padstr below the rotated labely, else label y goes below the scale bar 247 | ## Just adding spaces before labely doesn't work! 248 | padstr = '\n '*len(labely) 249 | textareafiller = TextArea(padstr,textprops=dict(size=label_fontsize/3.0)) 250 | textareay = TextArea(labely,textprops=dict(size=label_fontsize,rotation='vertical',color=color)) 251 | ## filler / pad string VPack-ed below labely 252 | textareayoffset = VPacker(children=[textareay, textareafiller], align="center", pad=0, sep=sep) 253 | ## now HPack this padded labely to the bars 254 | bars = HPacker(children=[textareayoffset, bars], align="top", pad=0, sep=sep) 255 | 256 | AnchoredOffsetbox.__init__(self, loc, pad=pad, borderpad=borderpad, 257 | child=bars, prop=prop, frameon=False, **kwargs) 258 | 259 | def add_scalebar(ax, matchx=True, matchy=True, hidex=True, hidey=True, \ 260 | label_fontsize=label_fontsize, color='k', **kwargs): 261 | """ Add scalebars to axes 262 | Adds a set of scale bars to *ax*, matching the size to the ticks of the plot 263 | and optionally hiding the x and y axes 264 | - ax : the axis to attach ticks to 265 | - matchx,matchy : if True, set size of scale bars to spacing between ticks 266 | if False, size should be set using sizex and sizey params 267 | - hidex,hidey : if True, hide x-axis and y-axis of parent 268 | - **kwargs : additional arguments passed to AnchoredScaleBars 269 | Returns created scalebar object 270 | """ 271 | def f(axis): 272 | l = axis.get_majorticklocs() 273 | return len(l)>1 and (l[1] - l[0]) 274 | 275 | if matchx: 276 | kwargs['sizex'] = f(ax.xaxis) 277 | kwargs['labelx'] = str(kwargs['sizex']) 278 | if matchy: 279 | kwargs['sizey'] = f(ax.yaxis) 280 | kwargs['labely'] = str(kwargs['sizey']) 281 | 282 | sb = AnchoredScaleBar(ax.transData, label_fontsize=label_fontsize, color=color, **kwargs) 283 | ax.add_artist(sb) 284 | 285 | if hidex : ax.xaxis.set_visible(False) 286 | if hidey : ax.yaxis.set_visible(False) 287 | 288 | return sb 289 | 290 | ## from https://gist.github.com/dmeliza/3251476#file-scalebars-py -- ends 291 | ## ------ 292 | 293 | ## Broken y-axis 294 | ## adapted from https://matplotlib.org/examples/pylab_examples/broken_axis.html 295 | def add_y_break_lines(ax1,ax2): 296 | ax1.spines['bottom'].set_visible(False) 297 | ax2.spines['top'].set_visible(False) 298 | ax1.xaxis.tick_top() 299 | ax1.tick_params(labeltop='off') # don't put tick labels at the top 300 | ax2.xaxis.tick_bottom() 301 | 302 | # add the break lines on the y-axis between ax1 and ax2 303 | # disable clipping; axes coordinates are in (0,1) 304 | d = .025 # length of diagonal break lines in axes coordinates 305 | # arguments to pass to plot, just so we don't keep repeating them 306 | kwargs = dict(transform=ax.transAxes, color='k', clip_on=False) 307 | # remember: plot takes x-list, y-list 308 | ax1.plot((-d, +d), (-d, +d), **kwargs) # top-left diagonal 309 | 310 | kwargs.update(transform=ax2.transAxes) # switch to the bottom axes 311 | ax2.plot((-d, +d), (1-d, 1+d), **kwargs) # bottom-left diagonal 312 | 313 | ## Broken x-axis 314 | ## adapted from https://matplotlib.org/examples/pylab_examples/broken_axis.html 315 | def add_x_break_lines(ax1,ax2,jutOut=0.1,breakSize=.025): 316 | ax1.spines['right'].set_visible(False) 317 | ax2.spines['left'].set_visible(False) 318 | ax1.yaxis.tick_left() 319 | ax2.yaxis.set_visible(False) 320 | # don't draw the x-axis, redrawn later 321 | ax1.spines['bottom'].set_visible(False) 322 | ax2.spines['bottom'].set_visible(False) 323 | 324 | # add the break lines on the y-axis between ax1 and ax2 325 | # disable clipping; axes coordinates are in (0,1) 326 | d = breakSize # length of diagonal break lines in axes coordinates 327 | # arguments to pass to plot, just so we don't keep repeating them 328 | kwargs = dict(transform=ax1.transAxes, color='k', clip_on=False, linewidth=plot_linewidth) 329 | # remember: plot takes x-list, y-list 330 | ax1.plot((0,1+jutOut), (0,0), **kwargs) # draw x-axis with a jutOut 331 | ax1.plot((1+jutOut-d, 1+jutOut+d), (-d, +d), **kwargs) # bottom-right diagonal 332 | 333 | kwargs.update(transform=ax2.transAxes) # switch to the right axes 334 | ax2.plot((-jutOut,1), (0,0), **kwargs) # draw x-axis with a jutOut 335 | ax2.plot((-jutOut-d, -jutOut+d), (-d, +d), **kwargs) # bottom-left diagonal 336 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | GNU GENERAL PUBLIC LICENSE 2 | Version 3, 29 June 2007 3 | 4 | Copyright (C) 2007 Free Software Foundation, Inc. 5 | Everyone is permitted to copy and distribute verbatim copies 6 | of this license document, but changing it is not allowed. 7 | 8 | Preamble 9 | 10 | The GNU General Public License is a free, copyleft license for 11 | software and other kinds of works. 12 | 13 | The licenses for most software and other practical works are designed 14 | to take away your freedom to share and change the works. By contrast, 15 | the GNU General Public License is intended to guarantee your freedom to 16 | share and change all versions of a program--to make sure it remains free 17 | software for all its users. We, the Free Software Foundation, use the 18 | GNU General Public License for most of our software; it applies also to 19 | any other work released this way by its authors. You can apply it to 20 | your programs, too. 21 | 22 | When we speak of free software, we are referring to freedom, not 23 | price. Our General Public Licenses are designed to make sure that you 24 | have the freedom to distribute copies of free software (and charge for 25 | them if you wish), that you receive source code or can get it if you 26 | want it, that you can change the software or use pieces of it in new 27 | free programs, and that you know you can do these things. 28 | 29 | To protect your rights, we need to prevent others from denying you 30 | these rights or asking you to surrender the rights. Therefore, you have 31 | certain responsibilities if you distribute copies of the software, or if 32 | you modify it: responsibilities to respect the freedom of others. 33 | 34 | For example, if you distribute copies of such a program, whether 35 | gratis or for a fee, you must pass on to the recipients the same 36 | freedoms that you received. You must make sure that they, too, receive 37 | or can get the source code. And you must show them these terms so they 38 | know their rights. 39 | 40 | Developers that use the GNU GPL protect your rights with two steps: 41 | (1) assert copyright on the software, and (2) offer you this License 42 | giving you legal permission to copy, distribute and/or modify it. 43 | 44 | For the developers' and authors' protection, the GPL clearly explains 45 | that there is no warranty for this free software. For both users' and 46 | authors' sake, the GPL requires that modified versions be marked as 47 | changed, so that their problems will not be attributed erroneously to 48 | authors of previous versions. 49 | 50 | Some devices are designed to deny users access to install or run 51 | modified versions of the software inside them, although the manufacturer 52 | can do so. This is fundamentally incompatible with the aim of 53 | protecting users' freedom to change the software. The systematic 54 | pattern of such abuse occurs in the area of products for individuals to 55 | use, which is precisely where it is most unacceptable. Therefore, we 56 | have designed this version of the GPL to prohibit the practice for those 57 | products. If such problems arise substantially in other domains, we 58 | stand ready to extend this provision to those domains in future versions 59 | of the GPL, as needed to protect the freedom of users. 60 | 61 | Finally, every program is threatened constantly by software patents. 62 | States should not allow patents to restrict development and use of 63 | software on general-purpose computers, but in those that do, we wish to 64 | avoid the special danger that patents applied to a free program could 65 | make it effectively proprietary. To prevent this, the GPL assures that 66 | patents cannot be used to render the program non-free. 67 | 68 | The precise terms and conditions for copying, distribution and 69 | modification follow. 70 | 71 | TERMS AND CONDITIONS 72 | 73 | 0. Definitions. 74 | 75 | "This License" refers to version 3 of the GNU General Public License. 76 | 77 | "Copyright" also means copyright-like laws that apply to other kinds of 78 | works, such as semiconductor masks. 79 | 80 | "The Program" refers to any copyrightable work licensed under this 81 | License. Each licensee is addressed as "you". "Licensees" and 82 | "recipients" may be individuals or organizations. 83 | 84 | To "modify" a work means to copy from or adapt all or part of the work 85 | in a fashion requiring copyright permission, other than the making of an 86 | exact copy. The resulting work is called a "modified version" of the 87 | earlier work or a work "based on" the earlier work. 88 | 89 | A "covered work" means either the unmodified Program or a work based 90 | on the Program. 91 | 92 | To "propagate" a work means to do anything with it that, without 93 | permission, would make you directly or secondarily liable for 94 | infringement under applicable copyright law, except executing it on a 95 | computer or modifying a private copy. Propagation includes copying, 96 | distribution (with or without modification), making available to the 97 | public, and in some countries other activities as well. 98 | 99 | To "convey" a work means any kind of propagation that enables other 100 | parties to make or receive copies. Mere interaction with a user through 101 | a computer network, with no transfer of a copy, is not conveying. 102 | 103 | An interactive user interface displays "Appropriate Legal Notices" 104 | to the extent that it includes a convenient and prominently visible 105 | feature that (1) displays an appropriate copyright notice, and (2) 106 | tells the user that there is no warranty for the work (except to the 107 | extent that warranties are provided), that licensees may convey the 108 | work under this License, and how to view a copy of this License. If 109 | the interface presents a list of user commands or options, such as a 110 | menu, a prominent item in the list meets this criterion. 111 | 112 | 1. Source Code. 113 | 114 | The "source code" for a work means the preferred form of the work 115 | for making modifications to it. "Object code" means any non-source 116 | form of a work. 117 | 118 | A "Standard Interface" means an interface that either is an official 119 | standard defined by a recognized standards body, or, in the case of 120 | interfaces specified for a particular programming language, one that 121 | is widely used among developers working in that language. 122 | 123 | The "System Libraries" of an executable work include anything, other 124 | than the work as a whole, that (a) is included in the normal form of 125 | packaging a Major Component, but which is not part of that Major 126 | Component, and (b) serves only to enable use of the work with that 127 | Major Component, or to implement a Standard Interface for which an 128 | implementation is available to the public in source code form. A 129 | "Major Component", in this context, means a major essential component 130 | (kernel, window system, and so on) of the specific operating system 131 | (if any) on which the executable work runs, or a compiler used to 132 | produce the work, or an object code interpreter used to run it. 133 | 134 | The "Corresponding Source" for a work in object code form means all 135 | the source code needed to generate, install, and (for an executable 136 | work) run the object code and to modify the work, including scripts to 137 | control those activities. However, it does not include the work's 138 | System Libraries, or general-purpose tools or generally available free 139 | programs which are used unmodified in performing those activities but 140 | which are not part of the work. For example, Corresponding Source 141 | includes interface definition files associated with source files for 142 | the work, and the source code for shared libraries and dynamically 143 | linked subprograms that the work is specifically designed to require, 144 | such as by intimate data communication or control flow between those 145 | subprograms and other parts of the work. 146 | 147 | The Corresponding Source need not include anything that users 148 | can regenerate automatically from other parts of the Corresponding 149 | Source. 150 | 151 | The Corresponding Source for a work in source code form is that 152 | same work. 153 | 154 | 2. Basic Permissions. 155 | 156 | All rights granted under this License are granted for the term of 157 | copyright on the Program, and are irrevocable provided the stated 158 | conditions are met. This License explicitly affirms your unlimited 159 | permission to run the unmodified Program. The output from running a 160 | covered work is covered by this License only if the output, given its 161 | content, constitutes a covered work. This License acknowledges your 162 | rights of fair use or other equivalent, as provided by copyright law. 163 | 164 | You may make, run and propagate covered works that you do not 165 | convey, without conditions so long as your license otherwise remains 166 | in force. You may convey covered works to others for the sole purpose 167 | of having them make modifications exclusively for you, or provide you 168 | with facilities for running those works, provided that you comply with 169 | the terms of this License in conveying all material for which you do 170 | not control copyright. Those thus making or running the covered works 171 | for you must do so exclusively on your behalf, under your direction 172 | and control, on terms that prohibit them from making any copies of 173 | your copyrighted material outside their relationship with you. 174 | 175 | Conveying under any other circumstances is permitted solely under 176 | the conditions stated below. Sublicensing is not allowed; section 10 177 | makes it unnecessary. 178 | 179 | 3. Protecting Users' Legal Rights From Anti-Circumvention Law. 180 | 181 | No covered work shall be deemed part of an effective technological 182 | measure under any applicable law fulfilling obligations under article 183 | 11 of the WIPO copyright treaty adopted on 20 December 1996, or 184 | similar laws prohibiting or restricting circumvention of such 185 | measures. 186 | 187 | When you convey a covered work, you waive any legal power to forbid 188 | circumvention of technological measures to the extent such circumvention 189 | is effected by exercising rights under this License with respect to 190 | the covered work, and you disclaim any intention to limit operation or 191 | modification of the work as a means of enforcing, against the work's 192 | users, your or third parties' legal rights to forbid circumvention of 193 | technological measures. 194 | 195 | 4. Conveying Verbatim Copies. 196 | 197 | You may convey verbatim copies of the Program's source code as you 198 | receive it, in any medium, provided that you conspicuously and 199 | appropriately publish on each copy an appropriate copyright notice; 200 | keep intact all notices stating that this License and any 201 | non-permissive terms added in accord with section 7 apply to the code; 202 | keep intact all notices of the absence of any warranty; and give all 203 | recipients a copy of this License along with the Program. 204 | 205 | You may charge any price or no price for each copy that you convey, 206 | and you may offer support or warranty protection for a fee. 207 | 208 | 5. Conveying Modified Source Versions. 209 | 210 | You may convey a work based on the Program, or the modifications to 211 | produce it from the Program, in the form of source code under the 212 | terms of section 4, provided that you also meet all of these conditions: 213 | 214 | a) The work must carry prominent notices stating that you modified 215 | it, and giving a relevant date. 216 | 217 | b) The work must carry prominent notices stating that it is 218 | released under this License and any conditions added under section 219 | 7. This requirement modifies the requirement in section 4 to 220 | "keep intact all notices". 221 | 222 | c) You must license the entire work, as a whole, under this 223 | License to anyone who comes into possession of a copy. This 224 | License will therefore apply, along with any applicable section 7 225 | additional terms, to the whole of the work, and all its parts, 226 | regardless of how they are packaged. This License gives no 227 | permission to license the work in any other way, but it does not 228 | invalidate such permission if you have separately received it. 229 | 230 | d) If the work has interactive user interfaces, each must display 231 | Appropriate Legal Notices; however, if the Program has interactive 232 | interfaces that do not display Appropriate Legal Notices, your 233 | work need not make them do so. 234 | 235 | A compilation of a covered work with other separate and independent 236 | works, which are not by their nature extensions of the covered work, 237 | and which are not combined with it such as to form a larger program, 238 | in or on a volume of a storage or distribution medium, is called an 239 | "aggregate" if the compilation and its resulting copyright are not 240 | used to limit the access or legal rights of the compilation's users 241 | beyond what the individual works permit. Inclusion of a covered work 242 | in an aggregate does not cause this License to apply to the other 243 | parts of the aggregate. 244 | 245 | 6. Conveying Non-Source Forms. 246 | 247 | You may convey a covered work in object code form under the terms 248 | of sections 4 and 5, provided that you also convey the 249 | machine-readable Corresponding Source under the terms of this License, 250 | in one of these ways: 251 | 252 | a) Convey the object code in, or embodied in, a physical product 253 | (including a physical distribution medium), accompanied by the 254 | Corresponding Source fixed on a durable physical medium 255 | customarily used for software interchange. 256 | 257 | b) Convey the object code in, or embodied in, a physical product 258 | (including a physical distribution medium), accompanied by a 259 | written offer, valid for at least three years and valid for as 260 | long as you offer spare parts or customer support for that product 261 | model, to give anyone who possesses the object code either (1) a 262 | copy of the Corresponding Source for all the software in the 263 | product that is covered by this License, on a durable physical 264 | medium customarily used for software interchange, for a price no 265 | more than your reasonable cost of physically performing this 266 | conveying of source, or (2) access to copy the 267 | Corresponding Source from a network server at no charge. 268 | 269 | c) Convey individual copies of the object code with a copy of the 270 | written offer to provide the Corresponding Source. This 271 | alternative is allowed only occasionally and noncommercially, and 272 | only if you received the object code with such an offer, in accord 273 | with subsection 6b. 274 | 275 | d) Convey the object code by offering access from a designated 276 | place (gratis or for a charge), and offer equivalent access to the 277 | Corresponding Source in the same way through the same place at no 278 | further charge. You need not require recipients to copy the 279 | Corresponding Source along with the object code. If the place to 280 | copy the object code is a network server, the Corresponding Source 281 | may be on a different server (operated by you or a third party) 282 | that supports equivalent copying facilities, provided you maintain 283 | clear directions next to the object code saying where to find the 284 | Corresponding Source. Regardless of what server hosts the 285 | Corresponding Source, you remain obligated to ensure that it is 286 | available for as long as needed to satisfy these requirements. 287 | 288 | e) Convey the object code using peer-to-peer transmission, provided 289 | you inform other peers where the object code and Corresponding 290 | Source of the work are being offered to the general public at no 291 | charge under subsection 6d. 292 | 293 | A separable portion of the object code, whose source code is excluded 294 | from the Corresponding Source as a System Library, need not be 295 | included in conveying the object code work. 296 | 297 | A "User Product" is either (1) a "consumer product", which means any 298 | tangible personal property which is normally used for personal, family, 299 | or household purposes, or (2) anything designed or sold for incorporation 300 | into a dwelling. In determining whether a product is a consumer product, 301 | doubtful cases shall be resolved in favor of coverage. For a particular 302 | product received by a particular user, "normally used" refers to a 303 | typical or common use of that class of product, regardless of the status 304 | of the particular user or of the way in which the particular user 305 | actually uses, or expects or is expected to use, the product. A product 306 | is a consumer product regardless of whether the product has substantial 307 | commercial, industrial or non-consumer uses, unless such uses represent 308 | the only significant mode of use of the product. 309 | 310 | "Installation Information" for a User Product means any methods, 311 | procedures, authorization keys, or other information required to install 312 | and execute modified versions of a covered work in that User Product from 313 | a modified version of its Corresponding Source. The information must 314 | suffice to ensure that the continued functioning of the modified object 315 | code is in no case prevented or interfered with solely because 316 | modification has been made. 317 | 318 | If you convey an object code work under this section in, or with, or 319 | specifically for use in, a User Product, and the conveying occurs as 320 | part of a transaction in which the right of possession and use of the 321 | User Product is transferred to the recipient in perpetuity or for a 322 | fixed term (regardless of how the transaction is characterized), the 323 | Corresponding Source conveyed under this section must be accompanied 324 | by the Installation Information. But this requirement does not apply 325 | if neither you nor any third party retains the ability to install 326 | modified object code on the User Product (for example, the work has 327 | been installed in ROM). 328 | 329 | The requirement to provide Installation Information does not include a 330 | requirement to continue to provide support service, warranty, or updates 331 | for a work that has been modified or installed by the recipient, or for 332 | the User Product in which it has been modified or installed. Access to a 333 | network may be denied when the modification itself materially and 334 | adversely affects the operation of the network or violates the rules and 335 | protocols for communication across the network. 336 | 337 | Corresponding Source conveyed, and Installation Information provided, 338 | in accord with this section must be in a format that is publicly 339 | documented (and with an implementation available to the public in 340 | source code form), and must require no special password or key for 341 | unpacking, reading or copying. 342 | 343 | 7. Additional Terms. 344 | 345 | "Additional permissions" are terms that supplement the terms of this 346 | License by making exceptions from one or more of its conditions. 347 | Additional permissions that are applicable to the entire Program shall 348 | be treated as though they were included in this License, to the extent 349 | that they are valid under applicable law. If additional permissions 350 | apply only to part of the Program, that part may be used separately 351 | under those permissions, but the entire Program remains governed by 352 | this License without regard to the additional permissions. 353 | 354 | When you convey a copy of a covered work, you may at your option 355 | remove any additional permissions from that copy, or from any part of 356 | it. (Additional permissions may be written to require their own 357 | removal in certain cases when you modify the work.) You may place 358 | additional permissions on material, added by you to a covered work, 359 | for which you have or can give appropriate copyright permission. 360 | 361 | Notwithstanding any other provision of this License, for material you 362 | add to a covered work, you may (if authorized by the copyright holders of 363 | that material) supplement the terms of this License with terms: 364 | 365 | a) Disclaiming warranty or limiting liability differently from the 366 | terms of sections 15 and 16 of this License; or 367 | 368 | b) Requiring preservation of specified reasonable legal notices or 369 | author attributions in that material or in the Appropriate Legal 370 | Notices displayed by works containing it; or 371 | 372 | c) Prohibiting misrepresentation of the origin of that material, or 373 | requiring that modified versions of such material be marked in 374 | reasonable ways as different from the original version; or 375 | 376 | d) Limiting the use for publicity purposes of names of licensors or 377 | authors of the material; or 378 | 379 | e) Declining to grant rights under trademark law for use of some 380 | trade names, trademarks, or service marks; or 381 | 382 | f) Requiring indemnification of licensors and authors of that 383 | material by anyone who conveys the material (or modified versions of 384 | it) with contractual assumptions of liability to the recipient, for 385 | any liability that these contractual assumptions directly impose on 386 | those licensors and authors. 387 | 388 | All other non-permissive additional terms are considered "further 389 | restrictions" within the meaning of section 10. If the Program as you 390 | received it, or any part of it, contains a notice stating that it is 391 | governed by this License along with a term that is a further 392 | restriction, you may remove that term. If a license document contains 393 | a further restriction but permits relicensing or conveying under this 394 | License, you may add to a covered work material governed by the terms 395 | of that license document, provided that the further restriction does 396 | not survive such relicensing or conveying. 397 | 398 | If you add terms to a covered work in accord with this section, you 399 | must place, in the relevant source files, a statement of the 400 | additional terms that apply to those files, or a notice indicating 401 | where to find the applicable terms. 402 | 403 | Additional terms, permissive or non-permissive, may be stated in the 404 | form of a separately written license, or stated as exceptions; 405 | the above requirements apply either way. 406 | 407 | 8. Termination. 408 | 409 | You may not propagate or modify a covered work except as expressly 410 | provided under this License. Any attempt otherwise to propagate or 411 | modify it is void, and will automatically terminate your rights under 412 | this License (including any patent licenses granted under the third 413 | paragraph of section 11). 414 | 415 | However, if you cease all violation of this License, then your 416 | license from a particular copyright holder is reinstated (a) 417 | provisionally, unless and until the copyright holder explicitly and 418 | finally terminates your license, and (b) permanently, if the copyright 419 | holder fails to notify you of the violation by some reasonable means 420 | prior to 60 days after the cessation. 421 | 422 | Moreover, your license from a particular copyright holder is 423 | reinstated permanently if the copyright holder notifies you of the 424 | violation by some reasonable means, this is the first time you have 425 | received notice of violation of this License (for any work) from that 426 | copyright holder, and you cure the violation prior to 30 days after 427 | your receipt of the notice. 428 | 429 | Termination of your rights under this section does not terminate the 430 | licenses of parties who have received copies or rights from you under 431 | this License. If your rights have been terminated and not permanently 432 | reinstated, you do not qualify to receive new licenses for the same 433 | material under section 10. 434 | 435 | 9. Acceptance Not Required for Having Copies. 436 | 437 | You are not required to accept this License in order to receive or 438 | run a copy of the Program. Ancillary propagation of a covered work 439 | occurring solely as a consequence of using peer-to-peer transmission 440 | to receive a copy likewise does not require acceptance. However, 441 | nothing other than this License grants you permission to propagate or 442 | modify any covered work. These actions infringe copyright if you do 443 | not accept this License. Therefore, by modifying or propagating a 444 | covered work, you indicate your acceptance of this License to do so. 445 | 446 | 10. Automatic Licensing of Downstream Recipients. 447 | 448 | Each time you convey a covered work, the recipient automatically 449 | receives a license from the original licensors, to run, modify and 450 | propagate that work, subject to this License. You are not responsible 451 | for enforcing compliance by third parties with this License. 452 | 453 | An "entity transaction" is a transaction transferring control of an 454 | organization, or substantially all assets of one, or subdividing an 455 | organization, or merging organizations. If propagation of a covered 456 | work results from an entity transaction, each party to that 457 | transaction who receives a copy of the work also receives whatever 458 | licenses to the work the party's predecessor in interest had or could 459 | give under the previous paragraph, plus a right to possession of the 460 | Corresponding Source of the work from the predecessor in interest, if 461 | the predecessor has it or can get it with reasonable efforts. 462 | 463 | You may not impose any further restrictions on the exercise of the 464 | rights granted or affirmed under this License. For example, you may 465 | not impose a license fee, royalty, or other charge for exercise of 466 | rights granted under this License, and you may not initiate litigation 467 | (including a cross-claim or counterclaim in a lawsuit) alleging that 468 | any patent claim is infringed by making, using, selling, offering for 469 | sale, or importing the Program or any portion of it. 470 | 471 | 11. Patents. 472 | 473 | A "contributor" is a copyright holder who authorizes use under this 474 | License of the Program or a work on which the Program is based. The 475 | work thus licensed is called the contributor's "contributor version". 476 | 477 | A contributor's "essential patent claims" are all patent claims 478 | owned or controlled by the contributor, whether already acquired or 479 | hereafter acquired, that would be infringed by some manner, permitted 480 | by this License, of making, using, or selling its contributor version, 481 | but do not include claims that would be infringed only as a 482 | consequence of further modification of the contributor version. For 483 | purposes of this definition, "control" includes the right to grant 484 | patent sublicenses in a manner consistent with the requirements of 485 | this License. 486 | 487 | Each contributor grants you a non-exclusive, worldwide, royalty-free 488 | patent license under the contributor's essential patent claims, to 489 | make, use, sell, offer for sale, import and otherwise run, modify and 490 | propagate the contents of its contributor version. 491 | 492 | In the following three paragraphs, a "patent license" is any express 493 | agreement or commitment, however denominated, not to enforce a patent 494 | (such as an express permission to practice a patent or covenant not to 495 | sue for patent infringement). To "grant" such a patent license to a 496 | party means to make such an agreement or commitment not to enforce a 497 | patent against the party. 498 | 499 | If you convey a covered work, knowingly relying on a patent license, 500 | and the Corresponding Source of the work is not available for anyone 501 | to copy, free of charge and under the terms of this License, through a 502 | publicly available network server or other readily accessible means, 503 | then you must either (1) cause the Corresponding Source to be so 504 | available, or (2) arrange to deprive yourself of the benefit of the 505 | patent license for this particular work, or (3) arrange, in a manner 506 | consistent with the requirements of this License, to extend the patent 507 | license to downstream recipients. "Knowingly relying" means you have 508 | actual knowledge that, but for the patent license, your conveying the 509 | covered work in a country, or your recipient's use of the covered work 510 | in a country, would infringe one or more identifiable patents in that 511 | country that you have reason to believe are valid. 512 | 513 | If, pursuant to or in connection with a single transaction or 514 | arrangement, you convey, or propagate by procuring conveyance of, a 515 | covered work, and grant a patent license to some of the parties 516 | receiving the covered work authorizing them to use, propagate, modify 517 | or convey a specific copy of the covered work, then the patent license 518 | you grant is automatically extended to all recipients of the covered 519 | work and works based on it. 520 | 521 | A patent license is "discriminatory" if it does not include within 522 | the scope of its coverage, prohibits the exercise of, or is 523 | conditioned on the non-exercise of one or more of the rights that are 524 | specifically granted under this License. You may not convey a covered 525 | work if you are a party to an arrangement with a third party that is 526 | in the business of distributing software, under which you make payment 527 | to the third party based on the extent of your activity of conveying 528 | the work, and under which the third party grants, to any of the 529 | parties who would receive the covered work from you, a discriminatory 530 | patent license (a) in connection with copies of the covered work 531 | conveyed by you (or copies made from those copies), or (b) primarily 532 | for and in connection with specific products or compilations that 533 | contain the covered work, unless you entered into that arrangement, 534 | or that patent license was granted, prior to 28 March 2007. 535 | 536 | Nothing in this License shall be construed as excluding or limiting 537 | any implied license or other defenses to infringement that may 538 | otherwise be available to you under applicable patent law. 539 | 540 | 12. No Surrender of Others' Freedom. 541 | 542 | If conditions are imposed on you (whether by court order, agreement or 543 | otherwise) that contradict the conditions of this License, they do not 544 | excuse you from the conditions of this License. If you cannot convey a 545 | covered work so as to satisfy simultaneously your obligations under this 546 | License and any other pertinent obligations, then as a consequence you may 547 | not convey it at all. For example, if you agree to terms that obligate you 548 | to collect a royalty for further conveying from those to whom you convey 549 | the Program, the only way you could satisfy both those terms and this 550 | License would be to refrain entirely from conveying the Program. 551 | 552 | 13. Use with the GNU Affero General Public License. 553 | 554 | Notwithstanding any other provision of this License, you have 555 | permission to link or combine any covered work with a work licensed 556 | under version 3 of the GNU Affero General Public License into a single 557 | combined work, and to convey the resulting work. The terms of this 558 | License will continue to apply to the part which is the covered work, 559 | but the special requirements of the GNU Affero General Public License, 560 | section 13, concerning interaction through a network will apply to the 561 | combination as such. 562 | 563 | 14. Revised Versions of this License. 564 | 565 | The Free Software Foundation may publish revised and/or new versions of 566 | the GNU General Public License from time to time. Such new versions will 567 | be similar in spirit to the present version, but may differ in detail to 568 | address new problems or concerns. 569 | 570 | Each version is given a distinguishing version number. If the 571 | Program specifies that a certain numbered version of the GNU General 572 | Public License "or any later version" applies to it, you have the 573 | option of following the terms and conditions either of that numbered 574 | version or of any later version published by the Free Software 575 | Foundation. If the Program does not specify a version number of the 576 | GNU General Public License, you may choose any version ever published 577 | by the Free Software Foundation. 578 | 579 | If the Program specifies that a proxy can decide which future 580 | versions of the GNU General Public License can be used, that proxy's 581 | public statement of acceptance of a version permanently authorizes you 582 | to choose that version for the Program. 583 | 584 | Later license versions may give you additional or different 585 | permissions. However, no additional obligations are imposed on any 586 | author or copyright holder as a result of your choosing to follow a 587 | later version. 588 | 589 | 15. Disclaimer of Warranty. 590 | 591 | THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY 592 | APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT 593 | HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY 594 | OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, 595 | THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 596 | PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM 597 | IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF 598 | ALL NECESSARY SERVICING, REPAIR OR CORRECTION. 599 | 600 | 16. Limitation of Liability. 601 | 602 | IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING 603 | WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS 604 | THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY 605 | GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE 606 | USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF 607 | DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD 608 | PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), 609 | EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF 610 | SUCH DAMAGES. 611 | 612 | 17. Interpretation of Sections 15 and 16. 613 | 614 | If the disclaimer of warranty and limitation of liability provided 615 | above cannot be given local legal effect according to their terms, 616 | reviewing courts shall apply local law that most closely approximates 617 | an absolute waiver of all civil liability in connection with the 618 | Program, unless a warranty or assumption of liability accompanies a 619 | copy of the Program in return for a fee. 620 | 621 | END OF TERMS AND CONDITIONS 622 | 623 | How to Apply These Terms to Your New Programs 624 | 625 | If you develop a new program, and you want it to be of the greatest 626 | possible use to the public, the best way to achieve this is to make it 627 | free software which everyone can redistribute and change under these terms. 628 | 629 | To do so, attach the following notices to the program. It is safest 630 | to attach them to the start of each source file to most effectively 631 | state the exclusion of warranty; and each file should have at least 632 | the "copyright" line and a pointer to where the full notice is found. 633 | 634 | {one line to give the program's name and a brief idea of what it does.} 635 | Copyright (C) {year} {name of author} 636 | 637 | This program is free software: you can redistribute it and/or modify 638 | it under the terms of the GNU General Public License as published by 639 | the Free Software Foundation, either version 3 of the License, or 640 | (at your option) any later version. 641 | 642 | This program is distributed in the hope that it will be useful, 643 | but WITHOUT ANY WARRANTY; without even the implied warranty of 644 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 645 | GNU General Public License for more details. 646 | 647 | You should have received a copy of the GNU General Public License 648 | along with this program. If not, see . 649 | 650 | Also add information on how to contact you by electronic and paper mail. 651 | 652 | If the program does terminal interaction, make it output a short 653 | notice like this when it starts in an interactive mode: 654 | 655 | {project} Copyright (C) {year} {fullname} 656 | This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. 657 | This is free software, and you are welcome to redistribute it 658 | under certain conditions; type `show c' for details. 659 | 660 | The hypothetical commands `show w' and `show c' should show the appropriate 661 | parts of the General Public License. Of course, your program's commands 662 | might be different; for a GUI interface, you would use an "about box". 663 | 664 | You should also get your employer (if you work as a programmer) or school, 665 | if any, to sign a "copyright disclaimer" for the program, if necessary. 666 | For more information on this, and how to apply and follow the GNU GPL, see 667 | . 668 | 669 | The GNU General Public License does not permit incorporating your program 670 | into proprietary programs. If your program is a subroutine library, you 671 | may consider it more useful to permit linking proprietary applications with 672 | the library. If this is what you want to do, use the GNU Lesser General 673 | Public License instead of this License. But first, please read 674 | . 675 | -------------------------------------------------------------------------------- /input_rec_transform_nengo_plot.py: -------------------------------------------------------------------------------- 1 | import matplotlib as mpl 2 | # must be called before any pylab import, matplotlib calls 3 | mpl.use('QT4Agg') 4 | 5 | import numpy as np 6 | import matplotlib.pyplot as plt 7 | from mpl_toolkits.mplot3d import Axes3D 8 | 9 | from nengo.utils.matplotlib import rasterplot 10 | 11 | #import pickle 12 | import shelve, contextlib 13 | from os.path import isfile 14 | import sys 15 | 16 | # presentation defaults for screenshot 17 | label_fontsize = 20 # pt 18 | plot_linewidth = 0.5 # pt 19 | linewidth = 1.0#0.5 20 | axes_linewidth = 0.5 21 | marker_size = 3.0 # markersize=<...> 22 | cap_size = 2.0 # for errorbar caps, capsize=<...> 23 | columnwidth = 85/25.4 # inches 24 | twocolumnwidth = 174/25.4 # inches 25 | linfig_height = columnwidth*2.0/3.0 26 | fig_dpi = 300 27 | 28 | def set_tick_widths(ax,tick_width): 29 | for tick in ax.xaxis.get_major_ticks(): 30 | tick.tick1line.set_markeredgewidth(tick_width) 31 | tick.tick2line.set_markeredgewidth(tick_width) 32 | for tick in ax.xaxis.get_minor_ticks(): 33 | tick.tick1line.set_markeredgewidth(tick_width) 34 | tick.tick2line.set_markeredgewidth(tick_width) 35 | for tick in ax.yaxis.get_major_ticks(): 36 | tick.tick1line.set_markeredgewidth(tick_width) 37 | tick.tick2line.set_markeredgewidth(tick_width) 38 | for tick in ax.yaxis.get_minor_ticks(): 39 | tick.tick1line.set_markeredgewidth(tick_width) 40 | tick.tick2line.set_markeredgewidth(tick_width) 41 | 42 | def axes_labels(ax,xtext,ytext,adjustpos=False,\ 43 | fontsize=label_fontsize,xpad=None,ypad=None): 44 | ax.set_xlabel(xtext,fontsize=fontsize,labelpad=xpad) 45 | # increase xticks text sizes 46 | for label in ax.get_xticklabels(): 47 | label.set_fontsize(fontsize) 48 | ax.set_ylabel(ytext,fontsize=fontsize,labelpad=ypad) 49 | # increase yticks text sizes 50 | for label in ax.get_yticklabels(): 51 | label.set_fontsize(fontsize) 52 | if adjustpos: 53 | ## [left,bottom,width,height] 54 | ax.set_position([0.135,0.125,0.84,0.75]) 55 | set_tick_widths(ax,axes_linewidth) 56 | 57 | 58 | def rates_CVs(spikesOut,trange,tCutoff,tMax,dt): 59 | '''takes nengo style spikesOut 60 | and returns rates and CVs of each neurons 61 | for spiketimes>tCutoff 62 | ''' 63 | n_times, n_neurons = spikesOut.shape 64 | CV = 100.*np.ones(n_neurons) 65 | rate = np.zeros(n_neurons) 66 | for i in range(n_neurons): 67 | spikesti = trange[spikesOut[:, i] > 0].ravel() 68 | spikesti = spikesti[np.where(spikesti>tCutoff)] 69 | #spikesti = spikest[where((spikest>(Tinit+300*ms)/second) & (spikesi==i))] 70 | # Brian style 71 | ISI = np.diff(spikesti)*dt 72 | if(len(spikesti)>5): 73 | CV[i] = np.std(ISI)/np.mean(ISI) 74 | rate[i]=len(spikesti)/(tMax-tCutoff) 75 | CV = CV[CV!=100.] 76 | return rate,CV 77 | 78 | def plot_data(dataFileName,endTag): 79 | print('reading data from',dataFileName+endTag+'.shelve') 80 | #data_dict = pickle.load( open( "/lcncluster/gilra/tmp/rec_learn_data.pickle", "rb" ) ) 81 | # with ensures that the file is closed at the end / if error 82 | with contextlib.closing( 83 | shelve.open(dataFileName+endTag+'.shelve', 'r') 84 | ) as data_dict: 85 | 86 | trange = data_dict['trange'] 87 | Tmax = data_dict['Tmax'] 88 | rampT = data_dict['rampT'] 89 | Tperiod = data_dict['Tperiod'] 90 | dt = data_dict['dt'] 91 | tau = data_dict['tau'] 92 | errorLearning = data_dict['errorLearning'] 93 | spikingNeurons = data_dict['spikingNeurons'] 94 | #EIfy = data_dict['EIfy'] 95 | #VSGInh2 = data_dict['VSGInh2'] 96 | 97 | Tnolearning = 4*Tperiod 98 | if 'Lorenz' in dataFileName: N = 3 99 | elif 'learnu' in dataFileName: N = 4 100 | elif 'robot2_' in dataFileName: N = 4 # end _ is important to disambiguate the next one, or interchange order 101 | elif 'robot2XY_' in dataFileName: N = 6 102 | elif 'robot1XY_' in dataFileName: N = 3 103 | elif 'mnist' in dataFileName: 104 | N = 10 105 | Tnolearning = data_dict['Tnolearning'] 106 | else: N = 2 107 | 108 | print('plotting data') 109 | plt.figure(facecolor='w',figsize=(8, 6*2)) # default figsize=(8,6) 110 | 111 | ### Plot Nengo network 112 | #EtoIdecvec = sim.data[EtoIdec] 113 | #print 'number of negative E to I decoders (should be 0) = ',\ 114 | # len(EtoIdecvec[where(EtoIdecvec<0)]) 115 | 116 | trange = data_dict['trange'] 117 | if errorLearning: # only start and end data is saved 118 | if 'start' in endTag: tidx = int(Tnolearning/dt) # Tnolearning 119 | else: tidx = int((Tnolearning+Tperiod)/dt) # (Tnolearning + Tperiod) if Tmax allows at least one noFlush Tperiod 120 | # (2*Tnolearning) if Tmax doesn't allow at least one noFlush Tperiod 121 | trange = trange[-tidx:] # data only for saved period 122 | y2 = data_dict['ratorOut2'] 123 | #yinh = data_dict['inhibrator'] 124 | #yinh2 = data_dict['inhibrator2'] 125 | rateEvolve = data_dict['rateEvolve'] 126 | 127 | ax = plt.subplot(2,1,1) 128 | ax2 = plt.subplot(2,1,2) 129 | #ax = plt.subplot(2,2,1) 130 | #ax2 = plt.subplot(2,2,3) 131 | #ax3 = plt.subplot(2,2,2) 132 | #ax4 = plt.subplot(2,2,4) 133 | #cnames = mpl.colors.cnames.values() # very similar colors grouped together 134 | cnames = ['r','g','b','c','m','y','k','olive','chocolate','lawngreen'] 135 | if errorLearning: 136 | recurrentLearning = data_dict['recurrentLearning'] 137 | if 'copycatLayer' in data_dict: copycatLayer = data_dict['copycatLayer'] 138 | else: copycatLayer = False 139 | err = data_dict['error_p'] 140 | #inpfn = lambda t: 0.02*np.array([0.23161279,-0.78227585])/0.1\ 141 | # if (t%1.0) < 0.1 else np.zeros(2) 142 | #plt.plot(trange, [inpfn(t) for t in trange], color='m', linewidth=1, label='u') 143 | if 'ratorOut' in data_dict: 144 | y = data_dict['ratorOut'] 145 | ax.plot(trange, y, color='b', linewidth=1, label='input $u$') 146 | if 'torqueOut' in data_dict: 147 | ax.plot(trange, data_dict['torqueOut'], color='r', linewidth=1, label='T1') 148 | if 'inverse' in dataFileName: 149 | ax.plot(trange, y2, color='r', linewidth=1, label='T1') 150 | if N>4: [ax2.plot(trange, y2[:,i], color=cnames[i], linewidth=1, label='L2') for i in range(N)] 151 | else: ax2.plot(trange, y2[:,:N], color='b', linewidth=1, label='pred $\hat{x}$') 152 | if 'robot' in dataFileName: 153 | pass 154 | #ax.plot(trange, y2[:,N:], color='b', linewidth=1, label='L2') 155 | if errorLearning: 156 | if recurrentLearning and copycatLayer: 157 | yExpect = data_dict['yExpectRatorOut'] 158 | ax2.plot(trange, yExpect[-tidx:], color='c', linewidth = 1, label='ref $x$') 159 | #elif '_func' in dataFileName: 160 | # yref = lambda x: (2*x[0]**2.,-10*x[0]**3+2*x[1]) 161 | # plt.plot(trange, np.array([yref(yval) for yval in y]), color='c', linewidth = 1, label='ref') 162 | else: 163 | if N>4: [ax2.plot(trange, rateEvolve[-tidx:,i], color=cnames[i], linewidth = 1, label='ref') for i in range(N)] 164 | else: ax2.plot(trange, rateEvolve[-tidx:], color='c', linewidth = 1, label='ref $x$') 165 | # all of the error is saved in _end.shelve, but we take only the end part here. 166 | if 'US2014' in dataFileName: 167 | ax.plot(trange, y2[:,:N]-rateEvolve[-tidx:], color='g', linewidth=1, label='err') 168 | ax3.plot(trange, err[-len(trange):,:3], linewidth=1, label='err') 169 | ax4.plot(trange, err[-len(trange):,3:6], linewidth=1, label='err') 170 | #ax3.plot(trange, err[-len(trange):], color='g', linewidth=1, label='err') 171 | else: 172 | ax.plot(trange, err[-len(trange):], color='g', linewidth=1, label='err $\epsilon$') 173 | #errMean = sim.data[errorMean_p] 174 | #plt.plot(trange, errMean, color='y', linewidth=1, label='errorM') 175 | else: 176 | ax2.plot(trange, rateEvolve, color='c', linewidth = 1, label='ref') 177 | #ax2.plot(trange, yinh2, color='k', linewidth=1, label='inh') 178 | axes_labels(ax,'time (s)','arb') 179 | axes_labels(ax2,'time (s)','arb') 180 | # each plot() above is 2-dimensional, but have only one label per plot 181 | handles, labels = ax.get_legend_handles_labels() 182 | ax.legend(handles[::2],labels[::2],loc="lower left") 183 | handles, labels = ax2.get_legend_handles_labels() 184 | ax2.legend(handles[::2],labels[::2],loc="lower left") 185 | #plt.xlim((trange[-1]-3.0,trange[-1])) 186 | formatter = mpl.ticker.ScalarFormatter(useOffset=False) # remove the offset on axes ticks 187 | ax.xaxis.set_major_formatter(formatter) 188 | 189 | ## inhibitory population 190 | if 'inhibrator' in data_dict.keys(): 191 | yinh = data_dict['inhibrator'] 192 | plt.subplot(2,2,2) 193 | plt.plot(trange, yinh) 194 | plt.xlabel('time (s)') 195 | 196 | ## plot distribution of CVs of spike trains 197 | ## Should take only the time range when the firing is stationary! 198 | ## but actually not stationary due to dynamics/stimulus, still taking. 199 | 200 | ## exc rates and CVs 201 | #if 'EspikesOut2' in data_dict.keys(): 202 | # if 'ExpectSpikesOut' in data_dict.keys(): 203 | # ExpectSpikesOut = data_dict['ExpectSpikesOut'] 204 | # ax=rasterplot(trange, ExpectSpikesOut[:,:100]) 205 | # axes_labels(ax,'time (s)','neuron #') 206 | # EspikesOut = data_dict['EspikesOut2'] 207 | # rateE,CVE = rates_CVs(EspikesOut,trange,\ 208 | # trange[0],trange[-1],dt) 209 | 210 | # ax = plt.subplot(2, 2, 3) 211 | # plt.hist(CVE,bins=100) 212 | # axes_labels(ax,'CV','count') 213 | # plt.title('CVs ('+str(trange[-1]-trange[0])+'s) histogram',fontsize=label_fontsize) 214 | 215 | # ax = plt.subplot(2, 2, 4) 216 | # plt.hist(rateE,bins=100,color='b',label='exc') 217 | # #if EIfy or VSGInh2: 218 | # # # inh rates and CVs 219 | # # IspikesOut = data_dict['IspikesOut2'] 220 | # # rateI,CVI = rates_CVs(IspikesOut,trange,\ 221 | # # trange[0],trange[-1],dt) 222 | # # plt.hist(rateI,bins=100,color='r',label='inh') 223 | # # plt.legend() 224 | # axes_labels(ax,'rate (Hz)','count') 225 | # plt.title('rates ('+str(trange[-1]-trange[0])+'s) histogram',fontsize=label_fontsize) 226 | 227 | # plt.subplot(2, 2, 2) 228 | # ax=rasterplot(trange, EspikesOut[:,0:100]) 229 | # axes_labels(ax,'time (s)','neuron #') 230 | # ax.xaxis.set_major_formatter(formatter) 231 | 232 | plt.tight_layout() 233 | 234 | # Vm analysis 235 | if spikingNeurons: 236 | plt.figure(facecolor='w',figsize=(8*2, 6)) # default figsize=(8,6) 237 | EVmOut = data_dict['EVmOut'] 238 | plt.subplot(1, 2, 1) 239 | plt.plot(trange,EVmOut[:,0],'b') 240 | plt.plot(trange,EVmOut[:,1],'r') 241 | plt.plot(trange,EVmOut[:,2],'g') 242 | plt.plot(trange,EVmOut[:,3],'y') 243 | plt.xlabel('time (s)') 244 | plt.ylabel('Vm') 245 | plt.title('Vm-s of a few neurons') 246 | 247 | plt.subplot(1, 2, 2) 248 | Vmlist = EVmOut.flatten() 249 | Vmrising = Vmlist[np.where(Vmlist>0.05)] 250 | plt.hist(Vmrising,normed=True,bins=100) 251 | plt.xlabel('Vm (0.05 to 1)') 252 | plt.ylabel('density (1/arb)') 253 | plt.title('(Vm>0.05) distribution') 254 | 255 | #plt.subplot(1, 3, 3) 256 | #EIn = data_dict['EIn'] 257 | #EOut = data_dict['EOut'] 258 | #plt.plot(trange,EIn[:,0],color='r',label='in') 259 | #plt.plot(trange,EIn[:,1],color='g',label='in') 260 | #plt.plot(trange,EIn[:,2],color='b',label='in') 261 | #plt.legend('lower left') 262 | #plt.xlabel('time (s)') 263 | #plt.ylabel('input') 264 | #plt.twinx() 265 | #plt.plot(trange,EOut[:,0],color='m',label='out') 266 | #plt.plot(trange,EOut[:,1],color='c',label='out') 267 | #plt.plot(trange,EOut[:,2],color='y',label='out') 268 | #plt.ylabel('output') 269 | #plt.legend() 270 | 271 | plt.tight_layout() 272 | 273 | ## Only for Lorenz attractor (func) 274 | #if 'func' in dataFileName and 'rec' in dataFileName: 275 | # fig = plt.figure(facecolor='w',figsize=(8*2, 6)) # default figsize=(8,6) 276 | # #ax = fig.add_subplot(121) 277 | # #ax.plot(trange,rateEvolve) 278 | # if 'start' in endTag: tstartidx = 0 279 | # elif 'end' in endTag: tstartidx = int(Tperiod/dt) # 3*Tperiod saved, skip first driven one 280 | # ax = fig.add_subplot(121, projection='3d') 281 | # if errorLearning and copycatLayer: 282 | # ax.plot(yExpect[tstartidx:,0],yExpect[tstartidx:,1],yExpect[tstartidx:,2]) 283 | # else: 284 | # tstartidx1 = int((Tmax-2*Tperiod)/dt) 285 | # ax.plot(rateEvolve[tstartidx1:,0],rateEvolve[tstartidx1:,1],rateEvolve[tstartidx1:,2]) 286 | # ax = fig.add_subplot(122, projection='3d') 287 | # if errorLearning: 288 | # ax.plot(y2[tstartidx:,0],y2[tstartidx:,1],y2[tstartidx:,2]) 289 | # # second layer output 290 | # else: 291 | # ax.plot(y[tstartidx:,0],y[tstartidx:,1],y[tstartidx:,2]) 292 | # first layer output 293 | 294 | def plot_weights(dataFileName): 295 | print('reading weights from',dataFileName) 296 | #data_dict = pickle.load( open( "/lcncluster/gilra/tmp/rec_learn_data.pickle", "rb" ) ) 297 | # with ensures that the file is closed at the end / if error 298 | with contextlib.closing( 299 | shelve.open(dataFileName, 'r') 300 | ) as data_dict: 301 | 302 | Tmax = data_dict['Tmax'] 303 | errorLearning = data_dict['errorLearning'] 304 | recurrentLearning = data_dict['recurrentLearning'] 305 | copycatLayer = data_dict['copycatLayer'] 306 | #EIfy = data_dict['EIfy'] 307 | #VSGInh2 = data_dict['VSGInh2'] 308 | # Weights analysis 309 | 310 | if errorLearning: 311 | plt.figure(facecolor='w',figsize=(8*2, 6*2)) # default figsize=(8,6) 312 | 313 | ax = plt.subplot(2,2,1) 314 | learnedWeights = data_dict['learnedWeights'] 315 | twtrange = np.linspace(0.0,Tmax,len(learnedWeights)) 316 | learnedWeightsFinal = learnedWeights[-1] 317 | print("plastic (FF/rec) Exc final weights") 318 | print(learnedWeightsFinal,learnedWeightsFinal.shape) 319 | mean_exc_wts = np.mean(learnedWeightsFinal[np.where(learnedWeightsFinal>=0)]) 320 | print("mean of exc positive weights = ",mean_exc_wts) 321 | plt.plot(twtrange,np.mean(np.mean(learnedWeights,axis=1),axis=1)*1e3,\ 322 | color='r',label='exc') 323 | 324 | learnedInhWeights = data_dict['learnedInhWeights'] 325 | learnedInhWeightsFinal = learnedInhWeights[-1] 326 | print("L2 Inh--|Exc weights") 327 | print(learnedInhWeightsFinal,learnedInhWeightsFinal.shape) 328 | mean_inh_wts = np.mean(learnedInhWeightsFinal) 329 | print("mean of L2 inh weights = ",mean_inh_wts) 330 | plt.plot(twtrange,np.mean(np.mean(learnedInhWeights,axis=1),axis=1)*1e3,\ 331 | color='b',label='inh') 332 | 333 | axes_labels(ax,'time (s)','mean weight (*1e-3 arb)') 334 | plt.legend() 335 | 336 | ax = plt.subplot(2, 2, 3) 337 | exc_wts_nonzero = learnedWeightsFinal[np.where(learnedWeightsFinal!=0)] 338 | plt.hist(exc_wts_nonzero.flatten()*1e3,bins=100,\ 339 | range=(-3*mean_exc_wts*1e3,3*mean_exc_wts*1e3)) 340 | axes_labels(ax,'exc weights (*1e-3 arb)','counts') 341 | plt.title('Histogram of EE weights != 0',fontsize=label_fontsize) 342 | 343 | ax = plt.subplot(2, 2, 4) 344 | inh_wts_nonzero = learnedInhWeightsFinal[np.where(learnedInhWeightsFinal!=0)] 345 | if len(inh_wts_nonzero)>0: 346 | plt.hist(inh_wts_nonzero.flatten()*1e3,bins=100,\ 347 | range=(8*mean_inh_wts*1e3,0)) 348 | axes_labels(ax,'inh weights (*1e-3 arb)','counts') 349 | plt.title('Histogram of inh weights',fontsize=label_fontsize) 350 | 351 | ## mean exc vs inh input (weights*firing_rates*tau) 352 | ## currently tau_EinE and tau_EI are both tau 353 | #plt.subplot(1, 4, 3) 354 | #plt.scatter(np.dot(learnedWeightsFinal,rateE)*tau,\ 355 | # np.dot(learnedInhWeightsFinal,rateI)*tau) 356 | #plt.xlabel('incoming exc input to a neuron (wt*rate*tau)') 357 | #plt.ylabel('incoming inh input to a neuron (wt*rate*tau)') 358 | #plt.title('Balance of EI inputs to L2 neuron') 359 | 360 | # exc and inh conns' output-s are same as the postsyn neurons' input-s 361 | # not separable into exc and inh contributions 362 | #plt.subplot(1, 4, 4) 363 | #learnedExcOut = data_dict['learnedExcOut'] 364 | #learnedInhOut = data_dict['learnedInhOut'] 365 | #plt.scatter(learnedExcOut[0][-1,:],learnedInhOut[0][-1,:]) 366 | #plt.xlabel('incoming exc input to a neuron (probed)') 367 | #plt.ylabel('incoming inh input to a neuron (probed)') 368 | 369 | ax = plt.subplot(2, 2, 2) 370 | print(learnedWeights.shape) 371 | for i in range(10): 372 | for j in range(10): 373 | plt.plot(twtrange,learnedWeights[:,i,j]) 374 | axes_labels(ax,'time (s)','weight (arb)') 375 | plt.title('evolution of a 100 exc->exc weights',fontsize=label_fontsize) 376 | 377 | plt.tight_layout() 378 | 379 | #if recurrentLearning and copycatLayer: 380 | # copycatWeights = data_dict['copycatWeights'] 381 | # copycatWeightsPert = data_dict['copycatWeightsPert'] 382 | # # I can only compare these weights if the seed (i.e. params) of the copycat ensemble 383 | # # are the same as the params of the learning ensemble 384 | # plt.figure(facecolor='w',figsize=(8*3, 6)) # default figsize=(8,6) 385 | # plt.subplot(1, 3, 1) 386 | # print learnedWeights.shape,copycatWeights.shape 387 | # #plt.scatter(learnedWeights[0].flatten(),copycatWeights[0].flatten()) 388 | # #plt.scatter(learnedWeights[0].flatten(),copycatWeights.flatten()) 389 | # #plt.xlabel('learned weights') 390 | # #plt.ylabel('ideal weights') 391 | # ccwt_fixed = copycatWeights.flatten() # ideal weights 392 | # ccwtPert_fixed = copycatWeightsPert.flatten() # perturbed initial weights 393 | # ccwtdiff = (ccwtPert_fixed-ccwt_fixed) 394 | # zero_wt_pert = 1e-6 395 | # zero_idxs = np.where(abs(ccwtdiff)0: 399 | # if len(zero_idxs)1.)[0])>0: 407 | # wts_notred = wts_varratio[np.where(abs(wts_varratio)>1.)] 408 | # print 'Weights which are not reducing',len(wts_notred),wts_notred 409 | # plt.hist( wts_notred, bins = 100 ) 410 | # else: 411 | # print 'All weights are reducing',wts_varratio 412 | # plt.xlabel('learned/ideal weights ratio') 413 | # plt.ylabel('count') 414 | # plt.title('learned moves towards ideal? start') 415 | 416 | # plt.subplot(1, 3, 2) 417 | # pert_idxs = np.where(abs(ccwtdiff/ccwt_fixed)>0.249) 418 | # plt.plot(twtrange,[ (learnedWeights[i].flatten()[pert_idxs] - ccwt_fixed[pert_idxs]) for i in range(len(twtrange))]) 419 | # axes_labels(ax,'time (s)','weight (arb)') 420 | # plt.title('diff of exc->exc weights from ideal goes to zero',fontsize=label_fontsize) 421 | 422 | # # data not available 423 | # #plt.subplot(1, 3, 2) 424 | # #wttmid = len(twtrange)/2 425 | # #plt.scatter(learnedWeights[wttmid].flatten(),copycatWeights[wttmid].flatten()) 426 | # #plt.xlabel('learned weights') 427 | # #plt.ylabel('ideal weights') 428 | # #plt.title('learned moves towards ideal? mid') 429 | 430 | # plt.subplot(1, 3, 3) 431 | # #plt.scatter(learnedWeights[-1].flatten(),copycatWeights[-1].flatten()) 432 | # #plt.scatter(learnedWeights[-1].flatten(),copycatWeights.flatten()) 433 | # #plt.xlabel('learned weights') 434 | # #plt.ylabel('ideal weights') 435 | # wts_varratio = (learnedWeights[-1].flatten()-ccwt_fixed) / ccwtdiff 436 | # if len(np.where(abs(wts_varratio)>1.)[0])>0: 437 | # wts_notred = wts_varratio[np.where(abs(wts_varratio)>1.)] 438 | # print 'Weights which are not reducing',len(wts_notred),wts_notred 439 | # plt.hist( wts_notred, bins = 100 ) 440 | # else: 441 | # print 'all weights reducing',wts_varratio 442 | # plt.xlabel('learned/ideal weights ratio') 443 | # plt.ylabel('count') 444 | # plt.title('learned moves towards ideal? end') 445 | 446 | # plt.tight_layout() 447 | 448 | def plot_currentvsexpected_weights(dataFileNameCurrent,dataFileNameExpected,weightStrs): 449 | for weightStr in weightStrs: 450 | if 'plastDecoders' in dataFileNameCurrent: plastDecoders = True 451 | else: plastDecoders = False 452 | print('reading weights from',dataFileNameCurrent) 453 | # with ensures that the file is closed at the end / if error 454 | with contextlib.closing( 455 | shelve.open(dataFileNameCurrent, 'r') 456 | ) as data_dict_current: 457 | if 'currentweights' in dataFileNameCurrent: 458 | current_decoders0 = data_dict_current['weights'+weightStr][0] 459 | current_decoders1 = data_dict_current['weights'+weightStr][-1] 460 | else: 461 | current_decoders1 = data_dict_current['learnedWeights'+weightStr] 462 | if 'initLearned' in dataFileNameCurrent and 'currentweights' in dataFileNameCurrent: 463 | expected_weights = current_decoders0 464 | print(expected_weights) 465 | else: 466 | print('reading weights from',dataFileNameExpected) 467 | with contextlib.closing( 468 | shelve.open(dataFileNameExpected, 'r') 469 | ) as data_dict_expected: 470 | if '_precopy' in dataFileNameExpected: 471 | expected_weights = data_dict_expected['weights'+weightStr] 472 | else: 473 | expected_weights = data_dict_expected['weights'+weightStr][-1] 474 | # can also use another _currentWeights file to compare insted of _expectWeights 475 | if not plastDecoders and '_expect' in dataFileNameExpected: 476 | encoders = data_dict_expected['encoders'] 477 | reprRadius = data_dict_expected['reprRadius'] 478 | expected_weights = np.dot(encoders,expected_weights)/reprRadius 479 | gain = data_dict_expected['gain'] 480 | # use below weights to compare against probed weights of EtoE = connection(neurons,neurons) 481 | expected_weights = gain.reshape(-1,1) * expected_weights 482 | 483 | print('plotting weights comparison ',weightStr) 484 | fig = plt.figure(facecolor='w',figsize=(8*2, 6*2)) # default figsize=(8,6) 485 | ax = plt.subplot(1,1,1) 486 | # since the data is large, and .flatten() gives memory error, I plot each row one by one 487 | for i in range(len(current_decoders1)): 488 | ax.scatter(current_decoders1[i,:],expected_weights[i,:],color='b',alpha=0.3) 489 | axes_labels(ax,'learned'+weightStr,'reference'+weightStr) 490 | print("done plotting weights comparison ",weightStr) 491 | 492 | def plot_current_weights(dataFileName): 493 | print('reading weights from',dataFileName) 494 | # with ensures that the file is closed at the end / if error 495 | if 'shelve' not in dataFileName: 496 | import pandas as pd 497 | with contextlib.closing( 498 | ( shelve.open(dataFileName, 'r') \ 499 | if 'shelve' in dataFileName \ 500 | else pd.HDFStore(dataFileName) ) 501 | ) as data_dict: 502 | weights = np.array(data_dict['weights']) 503 | if 'weightsIn' in data_dict.keys(): 504 | ff = True 505 | weightsIn = np.array(data_dict['weightsIn']) 506 | print(weightsIn.shape) 507 | print("Mean and SD of all InEtoE weights = ",np.mean(weightsIn[-1]),np.std(weightsIn[-1])) 508 | else: ff = False 509 | if 'encoders' in data_dict.keys(): 510 | encoders = data_dict['encoders'] 511 | reprRadius = data_dict['reprRadius'] 512 | weights = np.dot(encoders,weights)/reprRadius 513 | weights = np.swapaxes(weights,0,1) 514 | if 'inhWeights' in data_dict.keys(): 515 | inh = True 516 | inhWeights = data_dict['inhWeights'] 517 | print(inhWeights.shape) 518 | else: inh = False 519 | weightdt = data_dict['weightdt'] 520 | Tmax = data_dict['Tmax'] 521 | weighttimes = np.arange(0.0,Tmax+weightdt,weightdt)[:len(weights)] 522 | print(weights.shape) 523 | 524 | # Weights analysis 525 | plt.figure(facecolor='w',figsize=(8*2, 6*2)) # default figsize=(8,6) 526 | 527 | ax = plt.subplot(2,2,1) 528 | endweights = np.array(weights[-1]) 529 | print ("Mean and SD of all ratorOut2 weights = ",np.mean(endweights),np.std(endweights)) 530 | exc_wts_nonzero = endweights[np.where(endweights!=0)] 531 | mean_exc_wts = np.abs(np.mean(exc_wts_nonzero)) # abs() needed since if negative, 532 | # histogram range param below gives error xmin>xmax 533 | sd_exc_wts = np.std(exc_wts_nonzero) 534 | print ("Mean and SD of non-zero ratorOut2 weights = ",mean_exc_wts,sd_exc_wts) 535 | if inh: wide = mean_exc_wts 536 | else: wide = sd_exc_wts 537 | plt.hist(exc_wts_nonzero.flatten()*1e3,bins=500,\ 538 | range=(-2*wide*1e3,2*wide*1e3)) 539 | axes_labels(ax,'exc weights (*1e-3 arb)','counts') 540 | plt.title('Histogram of learnt weights != 0',fontsize=label_fontsize) 541 | 542 | ax = plt.subplot(2,2,2) 543 | absendweights = np.abs(endweights.flatten()) # absolute values of final learnt weights 544 | cutendweights = 0.60*np.max(absendweights) 545 | largewt_idxs = np.where(absendweights>cutendweights)[0] 546 | # Take only |weights| > 60% of the maximum 547 | if len(largewt_idxs)>0: 548 | # reshape weights to flatten axes 1,2, not the time axis 0 549 | # -1 below in reshape will mean total size / weights.shape[0] 550 | weightsflat = weights.reshape(weights.shape[0],-1) 551 | plt.plot( weighttimes, weightsflat[:,largewt_idxs] ) 552 | plt.xlabel('time (s)') 553 | plt.ylabel('weight (arb)') 554 | plt.title('Evolution of wts above 0.6*maxwt abs') 555 | 556 | if inh: 557 | weight_idxs = np.random.permutation(np.arange(inhWeights[-1].size))[:50] 558 | plt.plot( weighttimes, inhWeights.reshape(inhWeights.shape[0],-1)[:,weight_idxs] ) 559 | ax = plt.subplot(2,2,3) 560 | plt.hist(inhWeights.flatten(),bins=100) 561 | axes_labels(ax,'inh weights','counts') 562 | plt.title('Histogram of learnt inh weights',fontsize=label_fontsize) 563 | 564 | if ff: 565 | ax = plt.subplot(2,2,3) 566 | endweightsIn = np.array(weightsIn[-1]) 567 | absendweightsIn = np.abs(endweightsIn.flatten()) # absolute values of final learned weights 568 | cutendweightsIn = 0.60*np.max(absendweightsIn) 569 | largewt_idxs = np.where(absendweightsIn>cutendweightsIn)[0] 570 | # Take only |weights| > 60% of the maximum 571 | if len(largewt_idxs)>0: 572 | # reshape weights to flatten axes 1,2, not the time axis 0 573 | # -1 below in reshape will mean total size / weights.shape[0] 574 | weightsflat = weightsIn.reshape(weightsIn.shape[0],-1) 575 | plt.plot( weighttimes, weightsflat[:,largewt_idxs] ) 576 | plt.xlabel('time (s)') 577 | plt.ylabel('In weight (arb)') 578 | plt.title('Evolution of i/p wts above 0.6*maxwt abs') 579 | 580 | #ax = plt.subplot(2,2,3) 581 | startweights = np.array(weights[0]) 582 | ## since the data is large, and .flatten() gives memory error, I plot each row one by one 583 | #for i in range(len(endweights)): 584 | # ax.scatter(endweights[i,:],startweights[i,:],color='b',alpha=0.3) 585 | #axes_labels(ax,'learned','initial') 586 | 587 | if 'randomInitWeights' in dataFileName or 'initLearned' in dataFileName: 588 | # how many moved by more than x%? 589 | moved_fraction = (endweights-startweights)/startweights # element-by-element division 590 | moved_idxs = np.where(abs(moved_fraction)>10.) # ((row#s),(col#s)) 591 | print("Number of weights that moved by more than 1000% are",\ 592 | len(moved_idxs[0]),"out of",moved_fraction.size,\ 593 | "i.e.",len(moved_idxs[0])/float(moved_fraction.size)*100,"% of the weights.") 594 | else: 595 | # how many moved by more than x from zero? 596 | movement = endweights-startweights 597 | moved_idxs = np.where(abs(movement)>0.1) # ((row #s),(col #s)) 598 | print("Number of weights that moved by more than 0.1 are",\ 599 | len(moved_idxs[0]),"out of",movement.size,\ 600 | "i.e.",len(moved_idxs[0])/float(movement.size)*100,"% of the weights.") 601 | print("Neurons with 'strong' incoming weights",np.unique(moved_idxs[0])) # row #s are the post neurons 602 | print("Neurons with 'strong' outgoing weights",np.unique(moved_idxs[1])) # col #s are the pre neurons 603 | 604 | ax = plt.subplot(2,2,4) 605 | learnedWeightsFinal = endweights 606 | #print "plastic (FF/rec) Exc final weights" 607 | #print learnedWeightsFinal,learnedWeightsFinal.shape 608 | mean_exc_wts = np.mean(learnedWeightsFinal[np.where(learnedWeightsFinal>=0)]) 609 | print("mean of exc positive weights = ",mean_exc_wts) 610 | plt.plot(weighttimes,np.mean(np.mean(weights,axis=1),axis=1)*1e3,\ 611 | color='r',label='exc') 612 | 613 | if inh: 614 | inhWeightsFinal = inhWeights[-1] 615 | print("L2 Inh--|Exc weights") 616 | print(inhWeightsFinal,inhWeightsFinal.shape) 617 | mean_inh_wts = np.mean(inhWeightsFinal) 618 | print("mean of L2 inh weights = ",mean_inh_wts) 619 | plt.plot(weighttimes,np.mean(np.mean(inhWeights,axis=1),axis=1)*1e3,\ 620 | color='b',label='inh') 621 | 622 | axes_labels(ax,'time (s)','mean weight (*1e-3 arb)') 623 | plt.legend() 624 | 625 | plt.tight_layout() 626 | 627 | def plot_error_fulltime(dataFileName): 628 | # with ensures that the file is closed at the end / if error 629 | with contextlib.closing( 630 | shelve.open(dataFileName, 'r') 631 | ) as data_dict: 632 | 633 | trange = data_dict['trange'] 634 | Tmax = data_dict['Tmax'] 635 | Tperiod = data_dict['Tperiod'] 636 | dt = data_dict['dt'] 637 | err = data_dict['error_p'] 638 | # remove the Tnolearning period where error is forced to zero 639 | Tnolearning = 4*Tperiod 640 | Tmax = Tmax - Tnolearning 641 | # in the _end.shelve, error is available for the full time (not flushed) 642 | # remove the end part of Tnolearning or 100*Tperiod 643 | if trange[-1] > 1000: 644 | NperiodsAverage = 50 645 | trange = trange[:-int(NperiodsAverage*Tperiod/dt)] 646 | err = err[:-int(NperiodsAverage*Tperiod/dt)] 647 | else: 648 | NperiodsAverage = 1 649 | trange = trange[:-int(Tnolearning/dt)] 650 | err = err[:-int(Tnolearning/dt)] 651 | # bin squared error into every Tperiod 652 | numbins = int(Tmax/Tperiod) 653 | 654 | fig = plt.figure(facecolor='w') 655 | ax = plt.subplot(111) 656 | ax.plot(trange, np.linalg.norm(err,axis=1), linewidth=plot_linewidth) 657 | axes_labels(ax,'time (s)','error$^2$',xpad=-6,ypad=-7) 658 | 659 | #fig = plt.figure(facecolor='w') 660 | #ax = plt.subplot(111) 661 | ## mean error (not mean squared error as below) 662 | #points_per_bin = int(NperiodsAverage*Tperiod/dt) 663 | #if 'Lorenz' in dataFileName: N = 3 664 | #elif 'learnu' in dataFileName: N = 2 665 | #elif 'inverse' in dataFileName: N = 2 666 | #elif 'robot2' in dataFileName: N = 4 667 | #elif 'robot2XY' in dataFileName: N = 6 668 | #elif 'robot1XY' in dataFileName: N = 3 669 | #else: N = 2 670 | #for i in range(N): 671 | # err_mean = err[:,i].reshape((-1,points_per_bin)).mean(axis=1) 672 | # ax.plot(trange[::points_per_bin], err_mean,\ 673 | # color=['r','g','b','k','c','m','y'][i],linewidth=plot_linewidth) 674 | # ax.set_ylim(2*min(err_mean[-10:]),2*max(err_mean[-10:])) 675 | ## mean squared error 676 | #ax2 = plt.twinx() 677 | #points_per_bin = int(Tperiod/dt) 678 | #ax2.plot(trange[::points_per_bin], np.sum(err**2,axis=1).reshape((-1,points_per_bin)).mean(axis=1),\ 679 | # color='k', linewidth=plot_linewidth) 680 | #ax2.set_yscale('log') 681 | # 682 | #axes_labels(ax,'time (s)','error mean ('+str(NperiodsAverage)+'*Tperiod)',xpad=-6,ypad=-7) 683 | #axes_labels(ax2,'time (s)','error$^2$',xpad=-6,ypad=3) 684 | 685 | #fig = plt.figure(facecolor='w') 686 | #ax = plt.subplot(111) 687 | #for i in range(N): 688 | # miderr = len(err)//2 # python3 doesn't do integer division by default, use // 689 | # erri = err[miderr:,i] 690 | # err_reshape = erri.reshape((-1,points_per_bin)) 691 | # err_mean = err_reshape.mean(axis=0) 692 | # err_std = err_reshape.std(axis=0) 693 | # ax.plot(trange[:points_per_bin], err_mean,\ 694 | # color=['r','g','b','k','c','m','y'][i],linewidth=plot_linewidth) 695 | # ax.plot(trange[:points_per_bin], err_mean+err_std,\ 696 | # color=['r','g','b','k','c','m','y'][i],alpha=0.5,linewidth=plot_linewidth) 697 | # ax.plot(trange[:points_per_bin], err_mean-err_std,\ 698 | # color=['r','g','b','k','c','m','y'][i],alpha=0.5,linewidth=plot_linewidth) 699 | # print("Mean noise in dimension",i,"per time point in 2nd half of the sim is",erri.mean()) 700 | #axes_labels(ax,'time (s)','error',xpad=-6,ypad=-7) 701 | #ax.set_title('error Tperiod histogram (end half sim)') 702 | 703 | def plot_biases4nonfiringneurons(testFileName): 704 | # with ensures that the file is closed at the end / if error 705 | with contextlib.closing( 706 | shelve.open(testFileName+'_start.shelve', 'r') 707 | ) as data_dict: 708 | 709 | trange = data_dict['trange'] 710 | Tmax = data_dict['Tmax'] 711 | rampT = data_dict['rampT'] 712 | Tperiod = data_dict['Tperiod'] 713 | dt = data_dict['dt'] 714 | tau = data_dict['tau'] 715 | errorLearning = data_dict['errorLearning'] 716 | spikingNeurons = data_dict['spikingNeurons'] 717 | y2 = data_dict['ratorOut2'] 718 | if 'EspikesOut2' in data_dict.keys(): 719 | EspikesOut = data_dict['EspikesOut2'] 720 | 721 | tstart, tend = 0., 16. 722 | rate,CV = rates_CVs(EspikesOut,trange,tstart,tend,dt) 723 | zeroidxs = np.where(rate==0)[0] # indices of neurons that don't fire at all 724 | 725 | ## build an ensemble exactly as in the test file simulation 726 | ## and find the bises of those neurons 727 | ## NOTE: Set the seeds and other params manually below, 728 | ## as they could be ambiguous from name of the file 729 | import nengo 730 | Nexc, N, reprRadius, nrngain = 3000, 2, 5, 2 731 | seedR0, seedR2 = 2, 4 732 | gain_bias_set = True 733 | #biaslow, biashigh = 1 - nrngain, 1 + nrngain 734 | biaslow, biashigh = -nrngain, nrngain 735 | print('building model') 736 | mainModel = nengo.Network(label="Single layer network", seed=seedR0) 737 | with mainModel: 738 | ratorOut = nengo.Ensemble( Nexc, dimensions=N, radius=reprRadius, 739 | neuron_type=nengo.neurons.LIF(), 740 | bias=nengo.dists.Uniform(biaslow,biashigh), gain=np.ones(Nexc)*nrngain, 741 | #max_rates=nengo.dists.Uniform(200, 400), 742 | noise=None, seed=seedR2, label='ratorOut' ) 743 | sim = nengo.Simulator(mainModel,dt) 744 | biases = sim.data[ratorOut].bias 745 | zerofiringbiases = biases[zeroidxs] 746 | gains = sim.data[ratorOut].gain 747 | zerofiringgains = gains[zeroidxs] 748 | 749 | if gain_bias_set: histrange, biasrange = 5, 5 750 | else: histrange, biasrange = 500, 100 751 | fig = plt.figure(facecolor='w') 752 | ax1 = plt.subplot(231) 753 | vals,_,_ = ax1.hist(gains,bins=50,range=(0,histrange),color='k',histtype='step') 754 | ax1.set_xlabel('all gains') 755 | ax2 = plt.subplot(232) 756 | vals,_,_ = ax2.hist(biases,bins=50,range=(-histrange,biasrange),color='k',histtype='step') 757 | ax2.set_xlabel('all biases') 758 | ax3 = plt.subplot(234) 759 | vals,_,_ = ax3.hist(zerofiringgains,bins=50,range=(0,histrange),color='k',histtype='step') 760 | ax3.set_xlabel('zero-firing gains') 761 | ax4 = plt.subplot(235) 762 | vals,_,_ = ax4.hist(zerofiringbiases,bins=50,range=(-histrange,biasrange),color='k',histtype='step') 763 | ax4.set_xlabel('zero-firing biases') 764 | if not gain_bias_set: 765 | intercepts = sim.data[ratorOut].intercepts 766 | zerofiringintercepts = intercepts[zeroidxs] 767 | ax5 = plt.subplot(233) 768 | vals,_,_ = ax5.hist(intercepts,bins=50,color='k',histtype='step') 769 | ax5.set_xlabel('all intercepts') 770 | ax6 = plt.subplot(236) 771 | vals,_,_ = ax6.hist(zerofiringintercepts,bins=50,color='k',histtype='step') 772 | ax6.set_xlabel('zero-firing intercepts') 773 | 774 | plt.show() 775 | 776 | def plot_rec_nengo_all(dataFileName): 777 | if 'algo' not in dataFileName: 778 | plot_data(dataFileName,'_start') 779 | plot_data(dataFileName,'_end') 780 | plot_error_fulltime(dataFileName+'_end.shelve') 781 | 782 | ## .h5 is only for general system - robot arm, others use .shelve 783 | #if 'general' in dataFileName and 'robot' in dataFileName: 784 | # plot_current_weights(dataFileName+'_currentweights.h5') 785 | #else: 786 | # plot_current_weights(dataFileName+'_currentweights.shelve') 787 | 788 | ## only if copycatLayer 789 | #if 'ff_rec' in dataFileName: weightStrs = ['','In'] 790 | #else: weightStrs = [''] 791 | #if '_nocopycat' not in dataFileName: 792 | # if isfile(dataFileName+'_currentweights.shelve'): 793 | # plot_currentvsexpected_weights( 794 | # dataFileName+'_currentweights.shelve', 795 | # dataFileName+'_expectweights.shelve',weightStrs) 796 | # else: 797 | # plot_currentvsexpected_weights( 798 | # dataFileName+'_endweights.shelve', 799 | # dataFileName+'_expectweights.shelve',weightStrs) 800 | 801 | ### obsolete 802 | ##plot_weights(dataFileName+'_weights.shelve') 803 | else: 804 | plot_data(dataFileName,'') 805 | #plot_weights(dataFileName+'_weights.shelve') 806 | 807 | plt.show() 808 | 809 | if __name__ == "__main__": 810 | #plot_currentvsexpected_weights('../data/rec_learn_data_directfb_Nexc2000_seeds2345expconnseed0_nodeerr_plastDecoders_learn_rec_func_vanderPol_500.0s_expectweights.shelve', 811 | # '../data/rec_learn_data_directfb_Nexc2000_seeds2345expconnseed1_nodeerr_plastDecoders_learn_rec_func_vanderPol_500.0s_expectweights.shelve') 812 | #plt.show() 813 | 814 | plot_rec_nengo_all(sys.argv[1]) 815 | 816 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_algo_30.0s") 817 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_algo_func_30.0s.shelve") 818 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_EIfy_algo_2inhpops_3.0s_final.shelve") 819 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_EIfy_algo_2inhpops_func_3.0s_final.shelve") 820 | 821 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_None_noinh_3000.0s") 822 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_3000.0s") 823 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_400.0s_final.shelve") 824 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_func_400.0s.shelve") 825 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_func_400.0s.shelve") 826 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_noErrFB_func_400.0s.shelve") 827 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_None_noinh_1000.0s.shelve") 828 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_clip<0_noinh_400.0s_final.shelve") 829 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_inhdecaytau10_onetau2tau_data_learn_rec_clip<0_400.0s") 830 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_clip<0_func_1200.0s") 831 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_bothTau2_PES2e-3_learn_rec_clip<0_1200.0s") 832 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_bothTau2_PES2e-3_learn_rec_None_noinh_initLearned_func_100.0s_nostim") 833 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_inhdecay100_excdecay100_bothTau2_PES2e-3_learn_rec_clip<0_initLearned_func_400.0s_nostim") 834 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_gain10_inhdecay40_bothTau2_PES1e-3_learn_rec_clip<0_func_6000.0s_kickStart") 835 | #plot_rec_nengo_all("../data/rec_learn_data_wtf_Nexc2000_seeds0333_nodeerr_learn_rec_func_LinOsc_3000.0s") 836 | #plot_rec_nengo_all("../data/ff_ocl_g2oR4.5_wt80ms_Nexc3000_seeds2344_weightErrorCutoff0.0_nodeerr_learn_rec_nocopycat_func_vanderPol_trials_seed2by50.0amplVaryHeightsScaled_continueFrom4000.0_trials_seed9by50.0amplVaryHeightsScaled_1000.0s") 837 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_None_noinh_noErrFB_1200.0s_final.shelve") 838 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_None_noinh_noErrFB_func_1200.0s_final.shelve") 839 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_noinh_noErrFB_400.0s_final.shelve") 840 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_noinh_noErrFB_func_400.0s_final.shelve") 841 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_noinh_noErrFB_func_1200.0s_final.shelve") # worse with time! too high firing? 842 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_noErrFB_400.0s_final.shelve") 843 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_ff_clip<0_noErrFB_func_1200.0s_final.shelve") 844 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_None_noinh_noErrFB_400.0s_final.shelve") 845 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_clip<0_noinh_noErrFB_400.0s_final.shelve") 846 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_clip<0_noErrFB_400.0s_final.shelve") 847 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_None_noinh_func_400.0s.shelve") 848 | 849 | #plot_rec_nengo_all("/lcncluster/gilra/tmp/rec_learn_data_learn_rec_clip<0_400.0s_error2000_final.shelve") 850 | 851 | # NOTE: you need to set the gain / bias / max_rates params in the function, these are not obtained from the filename 852 | #plot_biases4nonfiringneurons("../data_draft4/ff_ocl_g2oR4.5_wt80ms_Nexc3000_seeds2344_weightErrorCutoff0.0_nodeerr_learn_rec_nocopycat_func_vanderPol_trials_seed2by50.0amplVaryHeightsScaled_testFrom5000.0_seed3by50.0rampLeaveRampHeights_40.0s") 853 | ## no EspikeOut saved for linear case! 854 | ##plot_biases4nonfiringneurons("../data_draft4/ff_ocl_Nexc2000_noinptau_seeds2344_weightErrorCutoff0.0_nodeerr_learn_rec_nocopycat_func_LinOsc_seed2by8.0amplVaryHeights_testFrom10000.0_seed2by8.0rampStep_20.0s") 855 | --------------------------------------------------------------------------------