diff --git a/crocoddyl/differential_action.py b/crocoddyl/differential_action.py index fceda169826f91d736559cae3e8bd860cc0d41e6..150dfc67f9a823aed091dd0f27a15b739dc5552a 100644 --- a/crocoddyl/differential_action.py +++ b/crocoddyl/differential_action.py @@ -323,6 +323,7 @@ class DifferentialActionDataNumDiff: self.Lxu = self.L[:ndx, ndx:] self.Luu = self.L[ndx:, ndx:] + class DifferentialActionModelActuated(DifferentialActionModelAbstract): def __init__(self, pinocchioModel, actuationModel, costModel): DifferentialActionModelAbstract.__init__(self, pinocchioModel.nq, pinocchioModel.nv, actuationModel.nu) diff --git a/crocoddyl/plots.py b/crocoddyl/plots.py index 0109d5f48147efc7334ea5df3bf455ce12b82de2..06de24eb664cab4242e2732663be0b2fa9069a86 100644 --- a/crocoddyl/plots.py +++ b/crocoddyl/plots.py @@ -1,33 +1,47 @@ import numpy as np import matplotlib.pyplot as plt + class PlotUAM: - def __init__(self, stateTraj, controlTraj, knots, dt, d, cf, cm): + def __init__(self, quadrotorType, stateTraj, controlTraj, knots, dt, d, cf, cm): self.stateTraj = stateTraj self.controlTraj = controlTraj self.knots = knots self.dt = dt + self.type = quadrotorType self.d = d self.cf = cf self.cm = cm self.PlotDataType = PlotDataUAM(self) + def plotFlyingPlatformState(self): + fig, axs = plt.subplots(1, 2, figsize=(15, 10)) + fig.suptitle('Motor forces') + t = self.PlotDataType.t_state + axs[0].plot(t, self.PlotDataType.state[:, 0], t, self.PlotDataType.state[:, 1], t, self.PlotDataType.state[:, 2]) + axs[0].legend(['x','y','z']) + axs[0].set_title('Position') + axs[1].plot(t, self.PlotDataType.state[:, 7], t, self.PlotDataType.state[:, 8], t, self.PlotDataType.state[:, 9]) + axs[1].legend(['x','y','z']) + axs[1].set_title('Velocity') + return fig, axs + def plotMotorForces(self): - fig, axs = plt.subplots(2,2, figsize=(15,10)) + fig, axs = plt.subplots(2, 2, figsize=(15, 10)) fig.suptitle('Motor forces') t = self.PlotDataType.t - axs[0, 0].plot(t,self.PlotDataType.control[:,0]) + axs[0, 0].plot(t, self.PlotDataType.control[:, 0]) axs[0, 0].set_title('Motor 1') - axs[0, 1].plot(t,self.PlotDataType.control[:,1]) + axs[0, 1].plot(t, self.PlotDataType.control[:, 1]) axs[0, 1].set_title('Motor 2') - axs[1, 0].plot(t,self.PlotDataType.control[:,2]) + axs[1, 0].plot(t, self.PlotDataType.control[:, 2]) axs[1, 0].set_title('Motor 3') - axs[1, 1].plot(t,self.PlotDataType.control[:,3]) + axs[1, 1].plot(t, self.PlotDataType.control[:, 3]) axs[1, 1].set_title('Motor 4') - return fig,axs + return fig, axs def plotFlyingPlatformActuation(self): - fig, axs = plt.subplots(1,2, figsize=(15,10)) + fig, axs = plt.subplots(1, 2, figsize=(15, 10)) fig.suptitle('Motor forces') t = self.PlotDataType.t axs[0].plot(t,self.PlotDataType.M[:,0], t,self.PlotDataType.M[:,1], t,self.PlotDataType.M[:,2]) @@ -46,17 +60,23 @@ class PlotUAM: # axs[0].legend(['M1','M2','M3','M4','M5','M6']) # return fig,axs + class PlotDataUAM(): def __init__(self, model): - self.t = np.arange(0, model.knots*model.dt, model.dt) - self.t_state = np.append(self.t, self.t[-1]+model.dt) + self.t = np.arange(0, round(model.knots * model.dt, 4), model.dt) + self.t_state = np.append(self.t, self.t[-1] + model.dt) self.control = np.vstack(model.controlTraj) - self.thrust = self.control[:,0]+self.control[:,1]+self.control[:,2]+self.control[:,3] - Mx = model.d*(-self.control[:,0]+self.control[:,1]+self.control[:,2]-self.control[:,3]) - My = model.d*(-self.control[:,0]+self.control[:,1]-self.control[:,2]+self.control[:,3]) - Mz = model.cm/model.cf*(-self.control[:,0]-self.control[:,1]+self.control[:,2]+self.control[:,3]) - - self.M = np.zeros([np.size(self.control,0), 3]) + self.state = np.vstack(model.stateTraj) + self.thrust = self.control[:, 0] + self.control[:, 1] + self.control[:, 2] + self.control[:, 3] + if model.type == 'x': + Mx = model.d * (-self.control[:, 0] + self.control[:, 1] + self.control[:, 2] - self.control[:, 3]) + My = model.d * (-self.control[:, 0] + self.control[:, 1] - self.control[:, 2] + self.control[:, 3]) + Mz = model.cm / model.cf * (-self.control[:, 0] - self.control[:, 1] + self.control[:, 2] + self.control[:, 3]) + elif model.type == '+': + Mx = model.d * (self.control[:, 1] - self.control[:, 3]) + My = model.d * (-self.control[:, 0] + self.control[:, 2]) + Mz = model.cm / model.cf * (-self.control[:, 0] + self.control[:, 1] - self.control[:, 2] + self.control[:, 3]) + self.M = np.zeros([np.size(self.control, 0), 3]) self.M[:, 0] = Mx self.M[:, 1] = My self.M[:, 2] = Mz diff --git a/crocoddyl/robots.py b/crocoddyl/robots.py index 25a51a77ceca6108152fc7bf6769302132709c60..fe0f1a861951d4f3b6230c24528e0d7c192827af 100644 --- a/crocoddyl/robots.py +++ b/crocoddyl/robots.py @@ -126,6 +126,7 @@ def loadHyQ(modelPath='/opt/openrobots/share/example-robot-data'): robot.model.referenceConfigurations["half_sitting"] = robot.q0 return robot + def loadKinton(modelPath='/opt/openrobots/share/example-robot-data'): URDF_FILENAME = "kinton_arm.urdf" URDF_SUBPATH = "/kinton_description/urdf/" + URDF_FILENAME @@ -136,12 +137,14 @@ def loadKinton(modelPath='/opt/openrobots/share/example-robot-data'): robot.model.referenceConfigurations["centered"] = robot.q0 return robot + def loadKintonArm(modelPath='/opt/openrobots/share/example-robot-data'): URDF_FILENAME = "kinton_arm.urdf" URDF_SUBPATH = "/kinton_description/urdf/" + URDF_FILENAME robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath]) return robot + def load2dofPlanar(modelPath='/home/pepms/robotics/other-tools/robot-data'): URDF_FILENAME = "2dof_planar.urdf" URDF_SUBPATH = "/2dof_planar/urdf/" + URDF_FILENAME @@ -149,7 +152,8 @@ def load2dofPlanar(modelPath='/home/pepms/robotics/other-tools/robot-data'): robot.q0.flat = [np.pi] return robot -def loadHector(modelPath='/home/pepms/robotics/other-tools/robot-data'): + +def loadHector(modelPath='/home/jmarti/robotics/other-tools/robot-data'): URDF_FILENAME = "quadrotor_base.urdf" URDF_SUBPATH = "/hector-description/urdf/" + URDF_FILENAME robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer()) diff --git a/examples/notebooks/2dof/acrobot.ipynb b/examples/notebooks/2dof/acrobot.ipynb index ec4b4a4cf70dae23480c15d7f388f86f68ff4037..7ef27e8313c0691896a6b31e32660269cb1c0e36 100644 --- a/examples/notebooks/2dof/acrobot.ipynb +++ b/examples/notebooks/2dof/acrobot.ipynb @@ -87,362 +87,21 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 2, "metadata": { "scrolled": true }, "outputs": [ { - "name": "stdout", - "output_type": "stream", - "text": [ - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 0 2.00201e+05 1.16096e+09 9.21968e+01 1.00000e+00 1.00000e+00 1.0000 1\n", - " 1 2.00200e+05 1.54461e+07 3.14734e+00 1.00000e+00 1.00000e+00 1.0000 1\n", - " 2 2.00199e+05 1.79399e+03 3.09626e-01 1.00000e+00 1.00000e+00 1.0000 1\n", - " 3 2.00199e+05 3.39328e+03 5.89887e-01 1.00000e+00 1.00000e+00 1.0000 1\n", - " 4 2.00197e+05 6.47120e+03 1.12549e+00 1.00000e+00 1.00000e+00 1.0000 1\n", - " 5 2.00195e+05 1.23441e+04 2.14841e+00 1.00000e+00 1.00000e+00 1.0000 1\n", - " 6 2.00190e+05 2.35492e+04 4.10323e+00 1.00000e+00 1.00000e+00 1.0000 1\n", - " 7 2.00180e+05 4.49270e+04 7.84407e+00 1.00000e+00 1.00000e+00 1.0000 1\n", - " 8 2.00162e+05 8.57134e+04 1.50217e+01 1.00000e+00 1.00000e+00 1.0000 1\n", - " 9 2.00128e+05 1.63545e+05 2.88639e+01 1.00000e+00 1.00000e+00 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 10 2.00061e+05 3.12250e+05 5.58218e+01 1.00000e+00 1.00000e+00 1.0000 1\n", - " 11 1.99929e+05 5.97981e+05 1.09351e+02 1.00000e+00 1.00000e+00 1.0000 1\n", - " 12 1.99660e+05 1.16043e+06 2.19929e+02 1.00000e+00 1.00000e+00 1.0000 1\n", - " 13 1.99065e+05 2.38449e+06 4.68916e+02 1.00000e+00 1.00000e+00 1.0000 1\n", - " 14 1.97416e+05 6.33753e+06 1.16250e+03 1.00000e+00 1.00000e+00 1.0000 1\n", - " 15 1.82461e+05 4.99746e+07 5.10514e+03 1.00000e+00 1.00000e+00 1.0000 1\n", - " 16 1.68743e+05 7.51342e+10 5.15698e+04 1.00000e+01 1.00000e+01 1.0000 1\n", - " 17 1.26802e+05 3.99501e+09 3.44668e+05 1.00000e+01 1.00000e+01 0.5000 1\n", - " 18 6.98759e+04 9.82853e+11 2.26947e+05 1.00000e+01 1.00000e+01 0.5000 1\n", - " 19 2.02725e+04 5.71522e+11 1.17776e+05 1.00000e+00 1.00000e+00 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 20 1.02926e+04 1.14975e+11 2.59392e+04 1.00000e+00 1.00000e+00 0.5000 1\n", - " 21 6.50756e+03 2.62667e+10 6.55275e+03 1.00000e-01 1.00000e-01 1.0000 1\n", - " 22 5.34085e+03 4.07997e+09 4.17908e+03 1.00000e-01 1.00000e-01 0.2500 1\n", - " 23 4.70136e+03 1.88124e+09 2.62343e+03 1.00000e-01 1.00000e-01 0.2500 1\n", - " 24 3.99760e+03 9.09931e+08 1.84358e+03 1.00000e-01 1.00000e-01 0.5000 1\n", - " 25 3.32742e+03 7.81105e+07 1.11239e+03 1.00000e-02 1.00000e-02 1.0000 1\n", - " 26 3.06404e+03 1.43324e+08 9.14533e+02 1.00000e-02 1.00000e-02 0.5000 1\n", - " 27 2.85334e+03 9.68882e+07 5.65338e+02 1.00000e-02 1.00000e-02 0.5000 1\n", - " 28 2.79953e+03 3.04477e+07 2.66526e+02 1.00000e-03 1.00000e-03 1.0000 1\n", - " 29 2.70925e+03 2.13333e+08 2.80254e+02 1.00000e-03 1.00000e-03 0.5000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 30 2.50004e+03 2.92098e+08 3.27901e+02 1.00000e-04 1.00000e-04 1.0000 1\n", - " 31 2.02035e+03 3.52509e+05 1.26929e+03 1.00000e-04 1.00000e-04 0.5000 1\n", - " 32 1.80103e+03 2.08929e+07 1.97848e+03 1.00000e-04 1.00000e-04 0.1250 1\n", - " 33 1.60557e+03 1.60392e+07 1.42325e+03 1.00000e-04 1.00000e-04 0.2500 1\n", - " 34 1.41725e+03 3.85125e+07 9.65434e+02 1.00000e-04 1.00000e-04 0.2500 1\n", - " 35 1.24798e+03 1.64564e+07 4.53406e+02 1.00000e-04 1.00000e-04 0.5000 1\n", - " 36 1.05211e+03 5.38901e+06 2.75515e+02 1.00000e-05 1.00000e-05 1.0000 1\n", - " 37 8.44057e+02 1.99724e+05 4.26936e+02 1.00000e-06 1.00000e-06 1.0000 1\n", - " 38 8.02529e+02 4.66864e+04 1.73189e+02 1.00000e-06 1.00000e-06 0.5000 1\n", - " 39 7.77646e+02 8.81186e+02 1.00350e+02 1.00000e-06 1.00000e-06 0.5000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 40 7.62149e+02 3.22748e+03 6.09360e+01 1.00000e-06 1.00000e-06 0.5000 1\n", - " 41 7.52141e+02 1.11324e+03 3.83520e+01 1.00000e-06 1.00000e-06 0.5000 1\n", - " 42 7.45253e+02 3.50300e+03 2.53379e+01 1.00000e-06 1.00000e-06 0.5000 1\n", - " 43 7.40273e+02 2.73430e+03 1.76460e+01 1.00000e-06 1.00000e-06 0.5000 1\n", - " 44 7.36427e+02 1.39565e+03 1.31192e+01 1.00000e-06 1.00000e-06 0.5000 1\n", - " 45 7.33270e+02 6.20272e+02 1.03678e+01 1.00000e-06 1.00000e-06 0.5000 1\n", - " 46 7.30557e+02 2.80257e+02 8.59548e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 47 7.28152e+02 1.42955e+02 7.37005e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 48 7.25979e+02 8.63697e+01 6.45943e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 49 7.23994e+02 6.07746e+01 5.73694e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 50 7.22170e+02 4.73969e+01 5.13265e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 51 7.20493e+02 3.90506e+01 4.60615e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 52 7.18951e+02 3.29214e+01 4.13491e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 53 7.17537e+02 2.79148e+01 3.70581e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 54 7.16245e+02 2.36222e+01 3.31178e+00 1.00000e-06 1.00000e-06 0.5000 1\n", - " 55 7.15889e+02 1.99076e+01 2.94888e+00 1.00000e-07 1.00000e-07 1.0000 1\n", - " 56 7.12990e+02 2.01704e+01 6.55642e+00 1.00000e-08 1.00000e-08 1.0000 1\n", - " 57 7.10845e+02 6.67999e+02 4.07708e+00 1.00000e-09 1.00000e-09 1.0000 1\n", - " 58 7.09461e+02 3.80830e+01 2.26922e+00 1.00000e-09 1.00000e-09 1.0000 1\n", - " 59 7.08542e+02 6.82361e+00 1.34000e+00 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 60 7.07909e+02 4.03002e+00 8.47089e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 61 7.07469e+02 2.73417e+00 5.52833e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 62 7.07165e+02 1.84088e+00 3.65584e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 63 7.06956e+02 1.23860e+00 2.43972e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 64 7.06812e+02 8.37368e-01 1.63849e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 65 7.06713e+02 5.67882e-01 1.10468e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 66 7.06646e+02 3.85585e-01 7.46353e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 67 7.06600e+02 2.61781e-01 5.04698e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 68 7.06569e+02 1.77570e-01 3.41303e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 69 7.06548e+02 1.20293e-01 2.30698e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 70 7.06533e+02 8.13736e-02 1.55814e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 71 7.06524e+02 5.49677e-02 1.05140e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 72 7.06517e+02 3.70811e-02 7.08778e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 73 7.06513e+02 2.49848e-02 4.77356e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 74 7.06510e+02 1.68167e-02 3.21213e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 75 7.06508e+02 1.13087e-02 2.15973e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 76 7.06507e+02 7.59883e-03 1.45112e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 77 7.06506e+02 5.10267e-03 9.74412e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 78 7.06505e+02 3.42460e-03 6.53968e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 79 7.06505e+02 2.29732e-03 4.38710e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 80 7.06505e+02 1.54053e-03 2.94196e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 81 7.06504e+02 1.03271e-03 1.97224e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 82 7.06504e+02 6.92113e-04 1.32181e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 83 7.06504e+02 4.63746e-04 8.85696e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 84 7.06504e+02 3.10676e-04 5.93365e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 85 7.06504e+02 2.08099e-04 3.97461e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 86 7.06504e+02 1.39374e-04 2.66203e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 87 7.06504e+02 9.33361e-05 1.78274e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 88 7.06504e+02 6.25004e-05 1.19379e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 89 7.06504e+02 4.18492e-05 7.99351e-06 1.00000e-09 1.00000e-09 1.0000 1\n" + "ename": "NameError", + "evalue": "name 'SolverFDDP' is not defined", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mNameError\u001b[0m Traceback (most recent call last)", + "\u001b[0;32m<ipython-input-2-e69df3cb07fe>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m 1\u001b[0m \u001b[0;31m# Creating the DDP solver for this OC problem, defining a logger\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 2\u001b[0;31m \u001b[0mddp\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mSolverFDDP\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mproblem\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 3\u001b[0m \u001b[0mddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcallback\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mCallbackDDPVerbose\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 4\u001b[0m \u001b[0mddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcallback\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mappend\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mCallbackDDPLogger\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 5\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;31mNameError\u001b[0m: name 'SolverFDDP' is not defined" ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 90 7.06504e+02 2.80200e-05 5.35208e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 91 7.06504e+02 1.87599e-05 3.58333e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 92 7.06504e+02 1.25596e-05 2.39903e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 93 7.06504e+02 8.40829e-06 1.60609e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 94 7.06504e+02 5.62898e-06 1.07521e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 95 7.06504e+02 3.76828e-06 7.19797e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 96 7.06504e+02 2.52261e-06 4.81856e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 97 7.06504e+02 1.68869e-06 3.22566e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 98 7.06504e+02 1.13043e-06 2.15931e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 99 7.06504e+02 7.56723e-07 1.44547e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 100 7.06504e+02 5.06554e-07 9.67603e-08 1.00000e-09 1.00000e-09 1.0000 1\n", - " 101 7.06504e+02 3.39087e-07 6.47715e-08 1.00000e-09 1.00000e-09 1.0000 1\n", - " 102 7.06504e+02 2.26984e-07 4.33579e-08 1.00000e-09 1.00000e-09 1.0000 1\n", - " 103 7.06504e+02 1.51942e-07 2.90235e-08 1.00000e-09 1.00000e-09 1.0000 1\n", - " 104 7.06504e+02 1.01709e-07 1.94281e-08 1.00000e-09 1.00000e-09 1.0000 1\n", - " 105 7.06504e+02 6.80828e-08 1.30050e-08 1.00000e-09 1.00000e-09 1.0000 1\n", - " 106 7.06504e+02 4.55739e-08 8.70541e-09 1.00000e-09 1.00000e-09 1.0000 1\n", - " 107 7.06504e+02 3.05066e-08 5.82730e-09 1.00000e-09 1.00000e-09 1.0000 1\n", - " 108 7.06504e+02 2.04207e-08 3.90072e-09 1.00000e-09 1.00000e-09 1.0000 1\n", - " 109 7.06504e+02 1.36693e-08 2.61109e-09 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 110 7.06504e+02 9.15005e-09 1.74782e-09 1.00000e-09 1.00000e-09 1.0000 1\n", - " 111 7.06504e+02 6.12490e-09 1.16997e-09 1.00000e-09 1.00000e-09 1.0000 1\n", - " 112 7.06504e+02 4.09991e-09 7.83156e-10 1.00000e-09 1.00000e-09 1.0000 1\n", - " 113 7.06504e+02 2.74441e-09 5.24232e-10 1.00000e-09 1.00000e-09 1.0000 1\n", - " 114 7.06504e+02 1.83707e-09 3.50913e-10 1.00000e-09 1.00000e-09 1.0000 1\n", - " 115 7.06504e+02 1.22970e-09 2.34895e-10 1.00000e-09 1.00000e-09 1.0000 1\n", - " 116 7.06504e+02 8.23141e-10 1.57235e-10 1.00000e-09 1.00000e-09 1.0000 1\n" - ] - }, - { - "data": { - "text/plain": [ - "([array([3.14, 0. , 0. , 0. ]),\n", - " array([ 3.18493482, -0.08713096, 4.49348194, -8.71309552]),\n", - " array([ 3.2298292 , -0.17422292, 4.48943827, -8.70919683]),\n", - " array([ 3.27463366, -0.26123502, 4.48044598, -8.70120942]),\n", - " array([ 3.31930113, -0.34813226, 4.46674667, -8.68972446]),\n", - " array([ 3.36378637, -0.43488521, 4.44852367, -8.67529474]),\n", - " array([ 3.4080461 , -0.52147097, 4.42597344, -8.65857575]),\n", - " array([ 3.45203903, -0.60787403, 4.39929332, -8.64030581]),\n", - " array([ 3.4957257 , -0.69408685, 4.36866653, -8.62128281]),\n", - " array([ 3.53906814, -0.78011023, 4.33424423, -8.60233717]),\n", - " array([ 3.58202938, -0.86595323, 4.29612405, -8.58430083]),\n", - " array([ 3.62457263, -0.95163295, 4.2543245 , -8.56797163]),\n", - " array([ 3.66666017, -1.03717368, 4.20875472, -8.55407264]),\n", - " array([ 3.70825196, -1.12260574, 4.15917857, -8.54320601]),\n", - " array([ 3.74930368, -1.20796374, 4.10517248, -8.53580074]),\n", - " array([ 3.78976444, -1.29328428, 4.04607602, -8.53205407]),\n", - " array([ 3.82957379, -1.37860295, 3.98093443, -8.53186644]),\n", - " array([ 3.86865812, -1.46395065, 3.90843271, -8.5347701 ]),\n", - " array([ 3.90692633, -1.54934918, 3.82682107, -8.53985257]),\n", - " array([ 3.94426465, -1.63480594, 3.73383282, -8.54567695]),\n", - " array([ 3.98053063, -1.72030798, 3.62659768, -8.55020316]),\n", - " array([ 4.01554619, -1.80581515, 3.50155634, -8.55071692]),\n", - " array([ 4.04909007, -1.89125292, 3.35438748, -8.54377767]),\n", - " array([ 4.08088973, -1.97650495, 3.17996605, -8.52520265]),\n", - " array([ 4.11061355, -2.06140607, 2.9723825 , -8.49011177]),\n", - " array([ 4.13786422, -2.14573673, 2.72506642, -8.43306615]),\n", - " array([ 4.16217494, -2.22922011, 2.43107181, -8.34833785]),\n", - " array([ 4.18301081, -2.31152354, 2.08358752, -8.23034349]),\n", - " array([ 4.19977803, -2.39226603, 1.67672214, -8.07424895]),\n", - " array([ 4.21184361, -2.47103299, 1.2065574 , -7.87669617]),\n", - " array([ 4.21856715, -2.54739816, 0.67235412, -7.63651698]),\n", - " array([ 4.21934356, -2.62095029, 0.07764073, -7.35521284]),\n", - " array([ 4.21365137, -2.69131985, -0.5692183 , -7.03695599]),\n", - " array([ 4.20109761, -2.75819961, -1.25537597, -6.68797565]),\n", - " array([ 4.18144808, -2.82135392, -1.96495324, -6.31543089]),\n", - " array([ 4.15463456, -2.88061511, -2.68135242, -5.92611935]),\n", - " array([ 4.12073641, -2.93586965, -3.38981479, -5.525454 ]),\n", - " array([ 4.07994156, -2.98703951, -4.07948487, -5.11698614]),\n", - " array([ 4.03249694, -3.03406423, -4.74446208, -4.70247228]),\n", - " array([ 3.97865966, -3.0768869 , -5.38372748, -4.28226633]),\n", - " array([ 3.91865772, -3.11544464, -6.00019469, -3.85577402]),\n", - " array([ 3.85266466, -3.14966263, -6.59930552, -3.42179966]),\n", - " array([ 3.78078902, -3.17945009, -7.18756462, -2.97874593]),\n", - " array([ 3.70307634, -3.20469726, -7.77126796, -2.52471678]),\n", - " array([ 3.61952115, -3.22527328, -8.3555189 , -2.05760147]),\n", - " array([ 3.5300861 , -3.24102531, -8.94350507, -1.57520325]),\n", - " array([ 3.43472662, -3.25177975, -9.53594786, -1.07544446]),\n", - " array([ 3.33342033, -3.25734622, -10.13062875, -0.55664642]),\n", - " array([ 3.22620107, -3.25752473, -10.72192632, -0.01785156]),\n", - " array([ 3.11319752, -3.25211597, -11.30035464, 0.54087625]),\n", - " array([ 2.99467581, -3.24093327, -11.85217104, 1.11826978]),\n", - " array([ 2.87108366, -3.22381409, -12.35921487, 1.71191798]),\n", - " array([ 2.74309134, -3.2006272 , -12.79923182, 2.31868886]),\n", - " array([ 2.61162144, -3.17127146, -13.14699083, 2.93557402]),\n", - " array([ 2.47785696, -3.13566294, -13.3764471 , 3.56085211]),\n", - " array([ 2.34321717, -3.09371085, -13.46397986, 4.19520901]),\n", - " array([ 2.20929372, -3.0452891 , -13.39234466, 4.84217551]),\n", - " array([ 2.07774808, -2.99021784, -13.1545638 , 5.50712605]),\n", - " array([ 1.95018035, -2.92827437, -12.75677323, 6.19434675]),\n", - " array([ 1.82798839, -2.85924962, -12.2191963 , 6.90247462]),\n", - " array([ 1.71224041, -2.78305121, -11.57479785, 7.61984101]),\n", - " array([ 1.60358529, -2.6998276 , -10.86551226, 8.32236121]),\n", - " array([ 1.50222254, -2.61006306, -10.13627404, 8.976454 ]),\n", - " array([ 1.40794413, -2.51459222, -9.42784116, 9.54708392]),\n", - " array([ 1.32023892, -2.41451805, -8.77052111, 10.0074172 ]),\n", - " array([ 1.23842745, -2.31106757, -8.18114766, 10.34504814]),\n", - " array([ 1.16178642, -2.20544538, -7.6641023 , 10.5622186 ]),\n", - " array([ 1.0896362 , -2.09873042, -7.21502244, 10.67149584]),\n", - " array([ 1.02138612, -1.99182797, -6.82500812, 10.69024557]),\n", - " array([ 0.95654761, -1.8854647 , -6.48385065, 10.63632652]),\n", - " array([ 0.8947285 , -1.78020782, -6.18191078, 10.52568849]),\n", - " array([ 0.83561923, -1.67649297, -5.91092732, 10.37148461]),\n", - " array([ 0.77897738, -1.5746524 , -5.66418506, 10.18405693]),\n", - " array([ 0.72461361, -1.4749394 , -5.43637709, 9.9713008 ]),\n", - " array([ 0.67238 , -1.37754814, -5.22336057, 9.73912544]),\n", - " array([ 0.62216096, -1.28262932, -5.02190441, 9.49188186]),\n", - " array([ 0.57386627, -1.19030217, -4.8294683 , 9.23271545]),\n", - " array([ 0.52742604, -1.10066377, -4.64402354, 8.96383942]),\n", - " array([ 0.48278691, -1.01379637, -4.46391333, 8.68674066]),\n", - " array([ 0.43990944, -0.92977304, -4.28774644, 8.40233236]),\n", - " array([ 0.39876627, -0.84866238, -4.11431701, 8.11106667]),\n", - " array([ 0.35934083, -0.7705322 , -3.94254454, 7.81301792]),\n", - " array([ 0.32162654, -0.69545275, -3.77142905, 7.50794454]),\n", - " array([ 0.28562636, -0.6234994 , -3.60001745, 7.1953355 ]),\n", - " array([ 0.25135258, -0.55475494, -3.42737839, 6.87444539]),\n", - " array([ 0.21882675, -0.48931173, -3.2525831 , 6.54432136]),\n", - " array([ 0.18807984, -0.42727349, -3.0746908 , 6.20382372]),\n", - " array([ 0.15915247, -0.36875707, -2.8927373 , 5.85164182]),\n", - " array([ 0.13209521, -0.31389401, -2.70572581, 5.48630617]),\n", - " array([ 0.10696901, -0.26283204, -2.51261927, 5.1061972 ]),\n", - " array([ 0.08384568, -0.21573653, -2.31233348, 4.70955131]),\n", - " array([ 0.06280837, -0.17279189, -2.10373072, 4.29446411]),\n", - " array([ 0.04395224, -0.13420298, -1.88561332, 3.85889105]),\n", - " array([ 0.02738507, -0.10019652, -1.65671694, 3.40064542]),\n", - " array([ 0.01322804, -0.07102258, -1.41570347, 2.91739391]),\n", - " array([ 1.61650040e-03, -4.69560835e-02, -1.16115350e+00, 2.40664990e+00]),\n", - " array([-0.00729909, -0.02829843, -0.89155866, 1.86576554]),\n", - " array([-0.01335223, -0.01537919, -0.60531455, 1.29192372]),\n", - " array([-0.01635938, -0.00855786, -0.30071529, 0.6821328 ]),\n", - " array([-0.01611896, -0.00822546, 0.02404208, 0.03323985]),\n", - " array([-0.01586976, -0.00809705, 0.02492077, 0.01284125])],\n", - " [array([-0.41707639]),\n", - " array([-0.02170736]),\n", - " array([-0.04339121]),\n", - " array([-0.06488339]),\n", - " array([-0.08608214]),\n", - " array([-0.10690605]),\n", - " array([-0.12728863]),\n", - " array([-0.14717918]),\n", - " array([-0.16654239]),\n", - " array([-0.18535658]),\n", - " array([-0.20361058]),\n", - " array([-0.22129932]),\n", - " array([-0.23841813]),\n", - " array([-0.25495595]),\n", - " array([-0.27088756]),\n", - " array([-0.28616505]),\n", - " array([-0.30070894]),\n", - " array([-0.31439939]),\n", - " array([-0.32706843]),\n", - " array([-0.33849405]),\n", - " array([-0.34839822]),\n", - " array([-0.3564508]),\n", - " array([-0.36228264]),\n", - " array([-0.36551154]),\n", - " array([-0.36578462]),\n", - " array([-0.36283921]),\n", - " array([-0.35657909]),\n", - " array([-0.34715357]),\n", - " array([-0.33501288]),\n", - " array([-0.32090036]),\n", - " array([-0.30574326]),\n", - " array([-0.29043471]),\n", - " array([-0.27556091]),\n", - " array([-0.26118713]),\n", - " array([-0.24681691]),\n", - " array([-0.23155717]),\n", - " array([-0.21440566]),\n", - " array([-0.19451738]),\n", - " array([-0.17134323]),\n", - " array([-0.14462508]),\n", - " array([-0.11430488]),\n", - " array([-0.08042383]),\n", - " array([-0.04306259]),\n", - " array([-0.00233759]),\n", - " array([0.04155727]),\n", - " array([0.0882841]),\n", - " array([0.13729043]),\n", - " array([0.18775348]),\n", - " array([0.23855829]),\n", - " array([0.28833105]),\n", - " array([0.3355495]),\n", - " array([0.37874419]),\n", - " array([0.41677769]),\n", - " array([0.44913947]),\n", - " array([0.47613113]),\n", - " array([0.49877609]),\n", - " array([0.51832359]),\n", - " array([0.53537352]),\n", - " array([0.54891866]),\n", - " array([0.55588481]),\n", - " array([0.55180844]),\n", - " array([0.53280124]),\n", - " array([0.49790594]),\n", - " array([0.4502027]),\n", - " array([0.39572102]),\n", - " array([0.34097891]),\n", - " array([0.2908931]),\n", - " array([0.2480415]),\n", - " array([0.21303487]),\n", - " array([0.18528336]),\n", - " array([0.16366376]),\n", - " array([0.14693799]),\n", - " array([0.13396036]),\n", - " array([0.12375473]),\n", - " array([0.115526]),\n", - " array([0.10864418]),\n", - " array([0.10262018]),\n", - " array([0.09708141]),\n", - " array([0.09175015]),\n", - " array([0.0864254]),\n", - " array([0.08096782]),\n", - " array([0.07528741]),\n", - " array([0.06933347]),\n", - " array([0.06308651]),\n", - " array([0.05655164]),\n", - " array([0.04975356]),\n", - " array([0.04273256]),\n", - " array([0.03554161]),\n", - " array([0.02824437]),\n", - " array([0.02091379]),\n", - " array([0.01363135]),\n", - " array([0.00648661]),\n", - " array([-0.00042301]),\n", - " array([-0.00699249]),\n", - " array([-0.01310974]),\n", - " array([-0.0186566]),\n", - " array([-0.02351091]),\n", - " array([-0.02754985]),\n", - " array([-0.03065489]),\n", - " array([-0.00059537])],\n", - " True)" - ] - }, - "execution_count": 5, - "metadata": {}, - "output_type": "execute_result" } ], "source": [ @@ -459,9 +118,21 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 1, "metadata": {}, - "outputs": [], + "outputs": [ + { + "ename": "NameError", + "evalue": "name 'displayTrajectory' is not defined", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mNameError\u001b[0m Traceback (most recent call last)", + "\u001b[0;32m<ipython-input-1-dfdd2464ed2c>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[0;32m----> 1\u001b[0;31m \u001b[0mdisplayTrajectory\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mrobot\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mxs\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mrunningModel\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mtimeStep\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m", + "\u001b[0;31mNameError\u001b[0m: name 'displayTrajectory' is not defined" + ] + } + ], "source": [ "displayTrajectory(robot, ddp.xs, runningModel.timeStep)" ] diff --git a/examples/notebooks/kinton/hector_flying_mission.ipynb b/examples/notebooks/kinton/hector_flying_mission.ipynb index 8c816bf1076776e9faeb85450dff8a143086bded..c7aeb3d021d837632f0cb4e080ee3ab9f2c9b576 100644 --- a/examples/notebooks/kinton/hector_flying_mission.ipynb +++ b/examples/notebooks/kinton/hector_flying_mission.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 26, + "execution_count": 5, "metadata": {}, "outputs": [], "source": [ @@ -14,7 +14,7 @@ }, { "cell_type": "code", - "execution_count": 27, + "execution_count": 10, "metadata": {}, "outputs": [], "source": [ @@ -30,7 +30,7 @@ }, { "cell_type": "code", - "execution_count": 28, + "execution_count": 11, "metadata": {}, "outputs": [], "source": [ @@ -39,7 +39,7 @@ " distanceRotorCOG = 0.1525\n", " cf = 6.6e-5\n", " cm = 1e-6\n", - " actModel = ActuationModelUAM(robot.model, distanceRotorCOG, cf, cm)\n", + " actModel = ActuationModelUAM(robot.model, '+', distanceRotorCOG, cf, cm)\n", "\n", " # COST MODEL\n", " # Create a cost model per the running and terminal action model.\n", @@ -53,13 +53,10 @@ "\n", " wBasePos = [1]\n", " wBaseOri = [1]\n", - " wArmPos = [1]\n", " wBaseVel = [10]\n", - " wBaseRate = [10]\n", - " wArmVel = [10] \n", " \n", - " stateWeights = np.array(wBasePos * 3 + wBaseOri * 3 + wArmPos * (robot.model.nv - 6) + wBaseVel * robot.model.nv)\n", - " controlWeights = np.array([0.1]*4 + [100]*6)\n", + " stateWeights = np.array(wBasePos * 3 + wBaseOri * 3 + BaseVel * robot.model.nv)\n", + " controlWeights = np.array([0.1]*4)\n", " \n", " goalTrackingCost = CostModelFramePlacement(rmodel,\n", " frame=rmodel.getFrameId(frameName),\n", @@ -100,7 +97,7 @@ }, { "cell_type": "code", - "execution_count": 29, + "execution_count": 12, "metadata": { "scrolled": true }, @@ -134,517 +131,22 @@ }, { "cell_type": "code", - "execution_count": 30, + "execution_count": 13, "metadata": { "scrolled": true }, "outputs": [ { - "name": "stdout", - "output_type": "stream", - "text": [ - "49\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 0 1.53271e+03 2.92603e+01 3.16146e+03 1.00000e-09 1.00000e-09 0.0078 0\n", - " 1 1.06352e+35 1.99241e+02 3.16513e+03 1.00000e-08 1.00000e-08 0.0020 0\n", - " 2 1.90957e+46 1.92461e+02 5.67382e+15 1.00000e-07 1.00000e-07 0.0020 0\n", - " 3 1.66200e+03 1.92118e+02 3.20631e+03 1.00000e-06 1.00000e-06 0.0020 0\n", - " 4 1.52483e+03 1.92791e+02 3.16110e+03 1.00000e-06 1.00000e-06 0.0039 0\n", - " 5 1.51849e+03 2.25174e+02 3.14188e+03 1.00000e-06 1.00000e-06 0.0078 0\n", - " 6 1.49611e+03 3.65879e+02 3.12458e+03 1.00000e-06 1.00000e-06 0.0156 0\n", - " 7 1.16189e+03 5.36795e+02 3.06635e+03 1.00000e-06 1.00000e-06 0.1250 0\n", - " 8 1.00372e+03 3.90854e+02 2.38571e+03 1.00000e-06 1.00000e-06 0.0625 0\n", - " 9 8.89988e+02 2.59809e+02 2.06477e+03 1.00000e-06 1.00000e-06 0.0625 0\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 10 8.81025e+02 4.04586e+02 1.86234e+03 1.00000e-06 1.00000e-06 0.0156 0\n", - " 11 7.75472e+02 4.67297e+02 1.80866e+03 1.00000e-06 1.00000e-06 0.0625 0\n", - " 12 6.40714e+02 4.44887e+02 1.58914e+03 1.00000e-06 1.00000e-06 0.1250 0\n", - " 13 6.13847e+02 5.08329e+02 1.33260e+03 1.00000e-06 1.00000e-06 0.0156 0\n", - " 14 5.91209e+02 5.80590e+02 1.26666e+03 1.00000e-06 1.00000e-06 0.0625 0\n", - " 15 4.91776e+02 8.13277e+02 1.23898e+03 1.00000e-06 1.00000e-06 0.0156 0\n", - " 16 4.84035e+02 2.14353e+02 1.01910e+03 1.00000e-06 1.00000e-06 0.0078 0\n", - " 17 4.32433e+02 2.17571e+02 9.99922e+02 1.00000e-06 1.00000e-06 0.0625 0\n", - " 18 4.03857e+02 2.06101e+02 8.94278e+02 1.00000e-06 1.00000e-06 0.0312 0\n", - " 19 3.78044e+02 1.74267e+02 8.32883e+02 1.00000e-06 1.00000e-06 0.1250 0\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 20 3.77158e+02 9.96151e+02 7.95167e+02 1.00000e-06 1.00000e-06 0.0039 0\n", - " 21 3.75501e+02 9.94156e+02 7.84670e+02 1.00000e-06 1.00000e-06 0.0039 0\n", - " 22 3.71323e+02 9.68994e+02 7.75764e+02 1.00000e-06 1.00000e-06 0.0156 0\n", - " 23 3.22253e+02 8.03569e+02 7.60195e+02 1.00000e-06 1.00000e-06 0.0625 0\n", - " 24 2.03545e+02 5.30764e+02 6.59037e+02 1.00000e-06 1.00000e-06 0.1250 0\n", - " 25 1.96419e+02 1.39872e+02 4.52954e+02 1.00000e-06 1.00000e-06 0.0156 0\n", - " 26 1.82267e+02 1.45859e+02 4.03301e+02 1.00000e-06 1.00000e-06 0.0625 0\n", - " 27 2.51878e+10 1.05273e+02 -9.43772e+03 1.00000e-06 1.00000e-06 0.1250 0\n" + "ename": "NameError", + "evalue": "global name 'BaseVel' is not defined", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mNameError\u001b[0m Traceback (most recent call last)", + "\u001b[0;32m<ipython-input-13-7c8226739a42>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m 1\u001b[0m \u001b[0mmodels\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 2\u001b[0m \u001b[0;32mfor\u001b[0m \u001b[0mi\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mrange\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;36m0\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mlen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mtarget_pos\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 3\u001b[0;31m \u001b[0mrunningModel\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mterminalModel\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0muavPlacementModel\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mtarget_pos\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mi\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mtarget_quat\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mi\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdt\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m'base_link'\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 4\u001b[0m \u001b[0mmodels\u001b[0m \u001b[0;34m+=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mrunningModel\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m*\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mT\u001b[0m\u001b[0;34m-\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mterminalModel\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 5\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;32m<ipython-input-11-8b96bca807aa>\u001b[0m in \u001b[0;36muavPlacementModel\u001b[0;34m(targetPos, targetQuat, integrationStep, frameName)\u001b[0m\n\u001b[1;32m 20\u001b[0m \u001b[0mwBaseVel\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0;36m10\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 21\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 22\u001b[0;31m \u001b[0mstateWeights\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0marray\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mwBasePos\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0;36m3\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0mwBaseOri\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0;36m3\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0mBaseVel\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0mrobot\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmodel\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mnv\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 23\u001b[0m \u001b[0mcontrolWeights\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0marray\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;36m0.1\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m*\u001b[0m\u001b[0;36m4\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 24\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", + "\u001b[0;31mNameError\u001b[0m: global name 'BaseVel' is not defined" ] - }, - { - "data": { - "text/plain": [ - "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.,\n", - " 0., 0., 0., 0., 0., 0., 0., 0.]),\n", - " array([-7.23779655e-05, -3.79136022e-05, 6.14093268e-01, 6.17069921e-05,\n", - " -1.16951328e-04, 1.20337610e-05, 9.99999991e-01, -3.67408013e-03,\n", - " -3.67331650e-04, 9.18454401e-04, -6.98548401e-04, -2.33562910e-04,\n", - " -1.76531563e-02, 4.74962429e-06, 8.02420743e-06, 1.22818655e+01,\n", - " 2.46827969e-03, -4.67805314e-03, 4.81350443e-04, -7.34816026e-02,\n", - " -7.34663300e-03, 1.83690880e-02, -1.39709680e-02, -4.67125820e-03,\n", - " -3.53063126e-01]),\n", - " array([ 1.49596078e-04, 1.95925337e-04, 7.40222876e-01, -1.28831957e-03,\n", - " 7.50453184e-04, 1.26375429e-05, 9.99998888e-01, -2.46045590e-03,\n", - " 3.81603710e-03, 7.93244808e-03, 7.66156117e-03, 1.21316669e-02,\n", - " -1.52022946e-02, 2.72330375e-03, 1.39850170e-03, 2.52259951e+00,\n", - " -5.40006622e-02, 3.46968413e-02, 2.83263172e-05, 2.42724846e-02,\n", - " 8.36673750e-02, 1.40279874e-01, 1.67202191e-01, 2.47304596e-01,\n", - " 4.90172341e-02]),\n", - " array([ 9.43827113e-05, -1.63910604e-06, 7.30901461e-01, 5.58196079e-03,\n", - " 1.17499840e-04, -6.12490110e-06, 9.99984414e-01, -7.36419390e-04,\n", - " 2.92207752e-02, 1.68274899e-02, 1.84056475e-02, 2.60389460e-02,\n", - " -1.00207907e-02, -8.56245824e-04, -3.81566739e-03, -1.86409824e-01,\n", - " 2.74812586e-01, -2.53203781e-02, -5.76879083e-04, 3.44807302e-02,\n", - " 5.08094761e-01, 1.77900836e-01, 2.14881728e-01, 2.78145582e-01,\n", - " 1.03630077e-01]),\n", - " array([ 4.32893270e-05, -4.98936505e-04, 7.22010848e-01, 8.01656701e-03,\n", - " -1.67188689e-04, -8.45092233e-06, 9.99967853e-01, 4.99976213e-04,\n", - " 4.84983878e-02, 2.87003211e-02, 3.09344778e-02, 4.05343493e-02,\n", - " -7.42000149e-03, -9.91750640e-04, -1.20312641e-02, -1.77660432e-01,\n", - " 9.73866071e-02, -1.13872201e-02, -1.80360325e-05, 2.47279120e-02,\n", - " 3.85552253e-01, 2.37456624e-01, 2.50576606e-01, 2.89908067e-01,\n", - " 5.20157850e-02]),\n", - " array([-2.03284300e-05, -1.53377290e-03, 7.21531454e-01, 7.89429121e-03,\n", - " -2.33493746e-04, -7.69766739e-06, 9.99968812e-01, 2.08430383e-03,\n", - " 6.51862806e-02, 4.23177821e-02, 4.47377330e-02, 5.58372859e-02,\n", - " -5.71544089e-03, -1.26676212e-03, -2.08633318e-02, -9.25686724e-03,\n", - " -4.89115520e-03, -2.65191040e-03, 5.22088358e-05, 3.16865523e-02,\n", - " 3.33757855e-01, 2.72349220e-01, 2.76065103e-01, 3.06058732e-01,\n", - " 3.40912119e-02]),\n", - " array([-9.65091836e-05, -2.97155730e-03, 7.21963192e-01, 8.05204724e-03,\n", - " -4.06505655e-04, -6.76413805e-06, 9.99967499e-01, 4.10245456e-03,\n", - " 8.42223237e-02, 5.66765362e-02, 5.92587009e-02, 7.17206020e-02,\n", - " -3.48712680e-03, -1.49395631e-03, -2.85928625e-02, 9.09318316e-03,\n", - " 6.31052140e-03, -6.91992951e-03, 9.04984596e-05, 4.03630146e-02,\n", - " 3.80720862e-01, 2.87175083e-01, 2.90419359e-01, 3.17666321e-01,\n", - " 4.45662819e-02]),\n", - " array([-1.92360720e-04, -4.79706888e-03, 7.21886932e-01, 8.43169771e-03,\n", - " -6.14046660e-04, -5.00976046e-06, 9.99964264e-01, 6.51998369e-03,\n", - " 1.04870663e-01, 7.14646182e-02, 7.41718651e-02, 8.79057839e-02,\n", - " -7.16755764e-04, -1.88957533e-03, -3.64786896e-02, -9.21233812e-04,\n", - " 1.51866524e-02, -8.30075548e-03, 1.30843948e-04, 4.83505827e-02,\n", - " 4.12966789e-01, 2.95761640e-01, 2.98263283e-01, 3.23703638e-01,\n", - " 5.54074207e-02]),\n", - " array([-3.18219173e-04, -7.03417341e-03, 7.21732209e-01, 8.67875016e-03,\n", - " -8.06841081e-04, -2.60083597e-06, 9.99962013e-01, 9.35510469e-03,\n", - " 1.26140057e-01, 8.64417153e-02, 8.92445077e-02, 1.04213021e-01,\n", - " 2.32433637e-03, -2.49441458e-03, -4.47548132e-02, -2.32488934e-03,\n", - " 9.88260167e-03, -7.71069470e-03, 1.55308390e-04, 5.67024199e-02,\n", - " 4.25387873e-01, 2.99541942e-01, 3.01452853e-01, 3.26144746e-01,\n", - " 6.08218427e-02]),\n", - " array([-4.83727709e-04, -9.69694345e-03, 7.21627985e-01, 8.73267387e-03,\n", - " -9.82107789e-04, 2.15894174e-07, 9.99961387e-01, 1.26786439e-02,\n", - " 1.47803439e-01, 1.01413320e-01, 1.04311959e-01, 1.20532335e-01,\n", - " 5.50558217e-03, -3.28906215e-03, -5.32762293e-02, -1.15103222e-03,\n", - " 2.15719316e-03, -7.00943882e-03, 1.71768386e-04, 6.64707839e-02,\n", - " 4.33267636e-01, 2.99432089e-01, 3.01349031e-01, 3.26386277e-01,\n", - " 6.36249159e-02]),\n", - " array([-6.97455872e-04, -1.27876383e-02, 7.21554844e-01, 8.58555224e-03,\n", - " -1.14067415e-03, 3.36021246e-06, 9.99962493e-01, 1.65675835e-02,\n", - " 1.69813042e-01, 1.16245317e-01, 1.19264544e-01, 1.36790008e-01,\n", - " 8.80453405e-03, -4.25514348e-03, -6.18499120e-02, -3.83050024e-04,\n", - " -5.88490221e-03, -6.34126674e-03, 1.86935773e-04, 7.77787928e-02,\n", - " 4.40192073e-01, 2.96639948e-01, 2.99051689e-01, 3.25153463e-01,\n", - " 6.59790376e-02]),\n", - " array([-9.67176738e-04, -1.62989368e-02, 7.21516171e-01, 8.20776546e-03,\n", - " -1.27955820e-03, 6.58979752e-06, 9.99965497e-01, 2.11304308e-02,\n", - " 1.92151371e-01, 1.30836756e-01, 1.34021388e-01, 1.52930917e-01,\n", - " 1.22260390e-02, -5.37662660e-03, -7.02803683e-02, 4.19005366e-04,\n", - " -1.51118079e-02, -5.55385678e-03, 1.94111274e-04, 9.12569464e-02,\n", - " 4.46766567e-01, 2.91828770e-01, 2.95136882e-01, 3.22818177e-01,\n", - " 6.84300988e-02]),\n", - " array([-1.29973199e-03, -2.02124338e-02, 7.21533697e-01, 7.56317229e-03,\n", - " -1.39291543e-03, 9.59817271e-06, 9.99970429e-01, 2.64863072e-02,\n", - " 2.14874049e-01, 1.45105626e-01, 1.48515981e-01, 1.68910522e-01,\n", - " 1.57989640e-02, -6.63432144e-03, -7.83422628e-02, 1.60262709e-03,\n", - " -2.57843338e-02, -4.53272278e-03, 1.90537728e-04, 1.07117526e-01,\n", - " 4.54453565e-01, 2.85377411e-01, 2.89891862e-01, 3.19592094e-01,\n", - " 7.14584998e-02]),\n", - " array([-1.70072829e-03, -2.44966063e-02, 7.21634956e-01, 6.61329357e-03,\n", - " -1.47415924e-03, 1.21046972e-05, 9.99977045e-01, 3.27388167e-02,\n", - " 2.38138102e-01, 1.58979630e-01, 1.62687303e-01, 1.84688218e-01,\n", - " 1.95848666e-02, -8.00313954e-03, -8.57752312e-02, 3.26264507e-03,\n", - " -3.79959242e-02, -3.24816516e-03, 1.77757968e-04, 1.25050191e-01,\n", - " 4.65281072e-01, 2.77480067e-01, 2.83426441e-01, 3.15553937e-01,\n", - " 7.57180530e-02]),\n", - " array([-2.17418561e-03, -2.91047299e-02, 7.21842386e-01, 5.32153952e-03,\n", - " -1.51730608e-03, 1.37068709e-05, 9.99984689e-01, 3.99716283e-02,\n", - " 2.62253978e-01, 1.72389741e-01, 1.76474095e-01, 2.00222269e-01,\n", - " 2.36931854e-02, -9.45155219e-03, -9.22820111e-02, 5.27661260e-03,\n", - " -5.16709391e-02, -1.72433441e-03, 1.51665573e-04, 1.44656232e-01,\n", - " 4.82317504e-01, 2.68202237e-01, 2.75735843e-01, 3.10681002e-01,\n", - " 8.21663753e-02]),\n", - " array([-2.72222464e-03, -3.39730695e-02, 7.22170978e-01, 3.65889458e-03,\n", - " -1.51624949e-03, 1.40834833e-05, 9.99992157e-01, 4.81779293e-02,\n", - " 2.87772146e-01, 1.85273079e-01, 1.89817621e-01, 2.15472177e-01,\n", - " 2.83232613e-02, -1.09423217e-02, -9.75299765e-02, 7.47933044e-03,\n", - " -6.65063760e-02, 4.37078789e-05, 1.15744966e-04, 1.64126020e-01,\n", - " 5.10363376e-01, 2.57666750e-01, 2.66870521e-01, 3.04998165e-01,\n", - " 9.26015190e-02]),\n", - " array([-3.34488775e-03, -3.90196283e-02, 7.22682334e-01, 1.57780103e-03,\n", - " -1.46029450e-03, 1.50546019e-05, 9.99997689e-01, 5.71733845e-02,\n", - " 3.15556526e-01, 1.97557364e-01, 2.02654102e-01, 2.30392268e-01,\n", - " 3.37514224e-02, -1.24325502e-02, -1.01159398e-01, 1.07927486e-02,\n", - " -8.32438686e-02, 2.23983341e-03, 1.56870383e-04, 1.79909104e-01,\n", - " 5.55687597e-01, 2.45685695e-01, 2.56729621e-01, 2.98401828e-01,\n", - " 1.08563220e-01]),\n", - " array([-4.03967814e-03, -4.41408310e-02, 7.23506644e-01, -1.04674947e-03,\n", - " -1.33776359e-03, 1.46495674e-05, 9.99998557e-01, 6.75699531e-02,\n", - " 3.46843608e-01, 2.09079940e-01, 2.14808142e-01, 2.44825988e-01,\n", - " 4.01998164e-02, -1.38692957e-02, -1.02772574e-01, 1.65797434e-02,\n", - " -1.04981903e-01, 4.90283646e-03, 1.29369773e-04, 2.07931373e-01,\n", - " 6.25741635e-01, 2.30451537e-01, 2.43080797e-01, 2.88674390e-01,\n", - " 1.28967881e-01]),\n", - " array([-4.79973907e-03, -4.92081019e-02, 7.24306598e-01, -4.15383256e-03,\n", - " -1.15512611e-03, -4.08403853e-06, 9.99990706e-01, 8.01971650e-02,\n", - " 3.83790871e-01, 2.20017534e-01, 2.26264343e-01, 2.58708437e-01,\n", - " 4.88024339e-02, -1.51879193e-02, -1.01850699e-01, 1.55101202e-02,\n", - " -1.24284569e-01, 7.30768534e-03, -5.75430750e-04, 2.52544237e-01,\n", - " 7.38945253e-01, 2.18751866e-01, 2.29124023e-01, 2.77648976e-01,\n", - " 1.72052350e-01]),\n", - " array([-5.61345395e-03, -5.40899308e-02, 7.23609600e-01, -6.79595899e-03,\n", - " -1.03540795e-03, 2.51360962e-06, 9.99976371e-01, 8.70885015e-02,\n", - " 4.31271994e-01, 2.31476487e-01, 2.38397271e-01, 2.73218956e-01,\n", - " 6.25309589e-02, -1.63221198e-02, -9.78384155e-02, -1.49722259e-02,\n", - " -1.05686295e-01, 4.78649756e-03, 4.05872743e-04, 1.37826731e-01,\n", - " 9.49622469e-01, 2.29179069e-01, 2.42658563e-01, 2.90210391e-01,\n", - " 2.74570500e-01]),\n", - " array([-6.47990254e-03, -5.86379142e-02, 7.23103406e-01, -8.66507350e-03,\n", - " -1.30524465e-03, 1.93013862e-05, 9.99961605e-01, 9.08772419e-02,\n", - " 4.96970173e-01, 2.41321485e-01, 2.50221454e-01, 2.87664435e-01,\n", - " 7.59263731e-02, -1.73194583e-02, -9.10469319e-02, -1.14882130e-02,\n", - " -7.47662037e-02, -1.07982067e-02, 6.75556957e-04, 7.57748079e-02,\n", - " 1.31396358e+00, 1.96899958e-01, 2.36483650e-01, 2.88909570e-01,\n", - " 2.67908284e-01]),\n", - " array([-7.44916692e-03, -6.23826834e-02, 7.41831647e-01, -1.08973049e-02,\n", - " -8.70143816e-04, -7.13726000e-06, 9.99940244e-01, 9.85784591e-02,\n", - " 5.84894504e-01, 2.48340301e-01, 2.59988184e-01, 3.00054039e-01,\n", - " 9.09964369e-02, -1.86323380e-02, -8.25124924e-02, 3.73069925e-01,\n", - " -8.92943518e-02, 1.74131520e-02, -7.90137885e-04, 1.54024343e-01,\n", - " 1.75848661e+00, 1.40376312e-01, 1.95334603e-01, 2.47792084e-01,\n", - " 3.01401276e-01]),\n", - " array([-8.60242134e-03, -6.64700290e-02, 7.98305864e-01, 1.60369141e-02,\n", - " -1.91467333e-03, -3.72298826e-04, 9.99869498e-01, 1.01967720e-01,\n", - " 7.58906550e-01, 2.50200168e-01, 2.74917626e-01, 3.14619108e-01,\n", - " 1.32286892e-01, -1.97448885e-02, -7.22877287e-02, 1.13011926e+00,\n", - " 1.07739162e+00, -4.16193265e-02, -1.60003159e-02, 6.77852178e-02,\n", - " 3.48024093e+00, 3.71973507e-02, 2.98588840e-01, 2.91301380e-01,\n", - " 8.25809098e-01]),\n", - " array([-1.30938616e-02, -9.86537232e-02, 5.43766269e-01, -1.38742011e-01,\n", - " 1.59262532e-02, -5.68736857e-04, 9.90200326e-01, 1.87858736e-01,\n", - " 6.25546403e-01, 2.83792613e-01, 2.70597447e-01, 3.32362274e-01,\n", - " 1.20336879e-01, -1.99542385e-02, -3.46133441e-02, -5.15189653e+00,\n", - " -6.20966764e+00, 7.13271661e-01, -7.62196270e-03, 1.71782033e+00,\n", - " -2.66720295e+00, 6.71848899e-01, -8.64035829e-02, 3.54863317e-01,\n", - " -2.39000251e-01]),\n", - " array([-6.68153435e-03, 1.18653609e-02, 7.24433267e-01, 5.02250202e-05,\n", - " -2.70264251e-02, 2.49664612e-03, 9.99631600e-01, -3.24026160e-02,\n", - " 1.11624718e+00, 2.47328758e-01, 3.85577706e-01, 5.09662780e-01,\n", - " 1.30386246e-01, 1.81544219e-01, 1.71215298e+00, 3.89808682e+00,\n", - " 5.56834444e+00, -1.72724202e+00, -2.84282901e-02, -4.40522705e+00,\n", - " 9.81401563e+00, -7.29277105e-01, 2.29960517e+00, 3.54601012e+00,\n", - " 2.00987335e-01]),\n", - " array([ 2.33715640e-02, 1.56117262e-01, 7.85245377e-01, -6.91593298e-02,\n", - " 9.67134179e-02, -7.22811716e-03, 9.92880283e-01, 6.33505686e-02,\n", - " 8.50264919e-01, 5.08225201e-01, 4.53250477e-01, 6.97647345e-01,\n", - " -2.70134962e-01, 4.82499592e-01, 2.78892400e+00, 1.45779533e+00,\n", - " -2.77487207e+00, 4.96412221e+00, -3.14664394e-01, 1.91506369e+00,\n", - " -5.31964531e+00, 5.21792886e+00, 1.35345543e+00, 3.75969130e+00,\n", - " -8.01042416e+00]),\n", - " array([ 2.49318233e-02, 2.84274889e-01, 7.06063913e-01, 9.06406792e-03,\n", - " 9.18018684e-03, -2.94379824e-03, 9.99912447e-01, 4.61390064e-02,\n", - " 9.50100284e-01, 3.91362497e-01, 4.08941393e-01, 7.12914490e-01,\n", - " -1.36987794e-01, 1.79232081e-01, 2.66814682e+00, -1.41833702e+00,\n", - " 3.14210206e+00, -3.50092498e+00, 2.33184775e-01, -3.44231244e-01,\n", - " 1.99670731e+00, -2.33725408e+00, -8.86181689e-01, 3.05342903e-01,\n", - " 2.66294335e+00]),\n", - " array([ 2.65350955e-02, 4.16042148e-01, 8.21679842e-01, -9.10360725e-02,\n", - " 1.68904585e-02, 2.44330540e-03, 9.95701349e-01, 9.18071187e-02,\n", - " 6.46339174e-01, 4.86762449e-01, 3.98497201e-01, 7.09937883e-01,\n", - " -2.82350007e-01, -3.28570666e-02, 2.42723875e+00, 2.52535842e+00,\n", - " -4.01178736e+00, 3.00603890e-01, 1.75713090e-01, 9.13362246e-01,\n", - " -6.07522222e+00, 1.90799904e+00, -2.08883828e-01, -5.95321481e-02,\n", - " -2.90724425e+00]),\n", - " array([ 2.04810440e-02, 5.05592210e-01, 7.04188274e-01, -2.33418299e-03,\n", - " 2.28748601e-02, -2.77204953e-03, 9.99731768e-01, 1.62194163e-01,\n", - " 7.40281271e-01, 5.37150395e-01, 4.09619051e-01, 7.28651657e-01,\n", - " -1.96581119e-01, -3.26386412e-02, 2.01747322e+00, -2.17787330e+00,\n", - " 3.55632041e+00, 2.46272717e-01, -1.26558537e-01, 1.40774089e+00,\n", - " 1.87884195e+00, 1.00775893e+00, 2.22436999e-01, 3.74275491e-01,\n", - " 1.71537776e+00]),\n", - " array([ 0.02199907, 0.59322613, 0.80071136, -0.05785012, -0.00608 ,\n", - " 0.00537088, 0.99829232, 0.10023439, 0.5369081 , 0.5612649 ,\n", - " 0.4482701 , 0.7647164 , -0.13613273, 0.00512148, 1.62660804,\n", - " 2.03428992, -2.22589648, -1.16425669, 0.2721511 , -1.2391955 ,\n", - " -4.06746348, 0.48229003, 0.77302096, 0.72129476, 1.20896784]),\n", - " array([ 0.03038133, 0.66139349, 0.65228701, 0.02823784, -0.00915887,\n", - " 0.00586246, 0.99954208, 0.08423737, 0.62572463, 0.67278887,\n", - " 0.49391044, 0.82276809, -0.15114221, 0.13902467, 1.46257328,\n", - " -2.93242729, 3.44424981, -0.14244892, -0.00871082, -0.31994036,\n", - " 1.77633062, 2.23047938, 0.91280675, 1.16103388, -0.3001897 ]),\n", - " array([ 0.03104884, 0.70837485, 0.77943271, -0.0311782 , -0.02351715,\n", - " 0.00565369, 0.99922115, 0.20280087, 0.44220075, 0.55904835,\n", - " 0.52624305, 0.85270528, -0.1773796 , 0.10909218, 0.92388191,\n", - " 2.54545158, -2.38011645, -0.56083816, 0.02973188, 2.37127001,\n", - " -3.67047766, -2.2748104 , 0.64665235, 0.59874383, -0.52474767]),\n", - " array([ 0.04294832, 0.74195723, 0.64102389, 0.03924969, -0.00752711,\n", - " 0.0064029 , 0.99918057, 0.24607385, 0.52664093, 0.71209244,\n", - " 0.55284623, 0.8863739 , -0.10137405, 0.15751559, 0.65695636,\n", - " -2.78186116, 2.82164504, 0.62274525, -0.01636894, 0.86545959,\n", - " 1.68880365, 3.06088195, 0.53206353, 0.67337243, 1.52011083]),\n", - " array([ 0.0604343 , 0.74723392, 0.77536892, 0.00742035, 0.04867119,\n", - " 0.00982831, 0.99873893, 0.17730904, 0.39904992, 0.90816418,\n", - " 0.65698385, 0.9678782 , -0.02899225, 0.23417637, 0.22214813,\n", - " 2.6933921 , -1.25688869, 2.26106371, 0.05841058, -1.37529617,\n", - " -2.55182012, 3.92143467, 2.0827523 , 1.630086 , 1.44763617]),\n", - " array([ 6.35304552e-02, 7.50382539e-01, 6.76706780e-01, 9.31922280e-04,\n", - " -9.70440478e-02, 7.37567468e-03, 9.95252322e-01, 4.30963615e-01,\n", - " 4.36171520e-01, 4.46691389e-01, 5.98173796e-01, 9.30298818e-01,\n", - " 2.46372724e-02, -1.31544447e-02, 4.51996896e-02, -1.98047188e+00,\n", - " -3.11792637e-01, -5.83336518e+00, -6.62276920e-02, 5.07309147e+00,\n", - " 7.42431966e-01, -9.22945576e+00, -1.17620098e+00, -7.51587681e-01,\n", - " 1.07259036e+00]),\n", - " array([ 2.45333075e-02, 7.47839261e-01, 7.95990552e-01, 4.57444022e-02,\n", - " 5.37194486e-02, 5.89211388e-03, 9.97490328e-01, 2.78703892e-01,\n", - " 4.88974157e-01, 1.04584798e+00, 6.81617363e-01, 9.97706184e-01,\n", - " 1.23493370e-01, -6.98428979e-01, 7.87577532e-02, 2.42794583e+00,\n", - " 1.83018024e+00, 6.02217701e+00, -2.40284129e-01, -3.04519445e+00,\n", - " 1.05605275e+00, 1.19831318e+01, 1.66887133e+00, 1.34814733e+00,\n", - " 1.97712196e+00]),\n", - " array([-6.47188841e-02, 7.70055039e-01, 6.33560677e-01, 1.60417960e-02,\n", - " 6.89049703e-02, 1.52043372e-03, 9.97493085e-01, 5.48159183e-01,\n", - " 6.98209888e-01, 9.03063171e-01, 8.30281048e-01, 1.12168095e+00,\n", - " 3.90855437e-01, -1.37187506e+00, 2.44033840e-01, -3.46449494e+00,\n", - " -1.17237596e+00, 6.05005910e-01, -2.66089608e-01, 5.38910582e+00,\n", - " 4.18471461e+00, -2.85569611e+00, 2.97327371e+00, 2.47949527e+00,\n", - " 5.34724134e+00]),\n", - " array([-1.21769787e-01, 8.00812386e-01, 9.05839287e-01, -5.09393885e-02,\n", - " -5.66350737e-02, -5.74146647e-03, 9.97078073e-01, 4.04115285e-01,\n", - " 5.46243740e-01, 7.10210026e-01, 5.68569190e-01, 8.95668558e-01,\n", - " -9.48278543e-02, -1.19753932e+00, 4.11289374e-01, 5.46860074e+00,\n", - " -2.66892004e+00, -5.02546942e+00, -3.95118222e-01, -2.88087795e+00,\n", - " -3.03932296e+00, -3.85706291e+00, -5.23423718e+00, -4.52024780e+00,\n", - " -9.71366583e+00]),\n", - " array([-0.1386908 , 0.79853223, 0.62135308, 0.0952355 , 0.13675888,\n", - " -0.01021301, 0.98596293, 0.66535168, 0.6981524 , 1.158194 ,\n", - " 0.94959568, 1.14969628, 0.09686113, 0.09943141, -0.28393278,\n", - " -5.74447958, 5.80987671, 7.80746613, -0.11915413, 5.22472782,\n", - " 3.03817315, 8.95967954, 7.62052973, 5.08055438, 3.83377976]),\n", - " array([-0.02206957, 0.69817907, 0.57339773, -0.00872902, -0.01865602,\n", - " -0.007195 , 0.99976197, 0.67790905, 0.72313127, 0.9120379 ,\n", - " 0.76987574, 1.06989721, 0.11712226, 2.49145663, -2.05296647,\n", - " -0.49996659, -4.13002422, -6.27259596, 0.14885394, 0.25114746,\n", - " 0.49957754, -4.92312212, -3.59439862, -1.5959813 , 0.40522262]),\n", - " array([ 9.68990484e-02, 5.91540114e-01, 7.90314478e-01, 4.68755896e-02,\n", - " 3.84948486e-02, 4.36069066e-03, 9.98149192e-01, 6.20696144e-01,\n", - " 6.11393703e-01, 1.25488469e+00, 9.44884763e-01, 1.15774835e+00,\n", - " -1.45151998e-01, 2.29182206e+00, -1.95331091e+00, 4.46789501e+00,\n", - " 2.21766808e+00, 2.29874376e+00, 4.40590887e-01, -1.14425810e+00,\n", - " -2.23475143e+00, 6.85693589e+00, 3.50018035e+00, 1.75702268e+00,\n", - " -5.24548527e+00]),\n", - " array([ 1.97362626e-01, 5.08393765e-01, 7.74759123e-01, -3.34278320e-01,\n", - " -3.91721334e-01, 1.64306118e-02, 8.57054512e-01, 4.12489147e-01,\n", - " 6.00889962e-01, 2.30595799e-01, 3.35731970e-01, 7.72926664e-01,\n", - " 5.31431177e-01, 1.79413327e+00, -1.57275423e+00, -1.55933659e+00,\n", - " -1.59924039e+01, -1.79303839e+01, 7.71912890e-01, -4.16413994e+00,\n", - " -2.10074820e-01, -2.04857779e+01, -1.21830559e+01, -7.69643363e+00,\n", - " 1.35316635e+01]),\n", - " array([ 1.69223915e-01, 5.25595635e-01, 8.89926421e-01, 1.44514675e-01,\n", - " 1.58902589e-01, 1.82525899e-02, 9.76489794e-01, 3.59117673e-01,\n", - " 1.47484707e+00, 1.39309715e+00, 1.11357490e+00, 1.17802970e+00,\n", - " 9.45127804e-01, -2.93285434e-02, -6.96963527e-02, 2.66401260e+00,\n", - " 2.02859428e+01, 2.24990063e+01, -1.71651569e-01, -1.06742948e+00,\n", - " 1.74791422e+01, 2.32500270e+01, 1.55568585e+01, 8.10206077e+00,\n", - " 8.27393254e+00]),\n", - " array([-1.10384135e-02, 6.56370496e-01, 8.60872030e-01, 5.45824335e-02,\n", - " 2.45618732e-01, 3.36600331e-02, 9.67243092e-01, 1.47430915e+00,\n", - " 3.33818092e+00, 2.12690074e+00, 7.40243584e-01, 1.26717285e+00,\n", - " 9.01221233e-01, -2.85221805e+00, 2.46492498e+00, -2.44888974e+00,\n", - " -3.50319096e+00, 3.61018441e+00, -4.65566118e-01, 2.23038296e+01,\n", - " 3.72666770e+01, 1.46760718e+01, -7.46662626e+00, 1.78286293e+00,\n", - " -8.78131423e-01]),\n", - " array([ -0.03416916, 0.76218246, 1.00651423, 0.21603177,\n", - " 0.50763602, -0.03832942, 0.83316673, 0.45797655,\n", - " 4.02091595, 1.03609473, 1.00538763, 1.56332796,\n", - " 1.27069799, -2.24274985, 2.77857885, 1.12302608,\n", - " 7.75212514, 11.30304132, -1.62259914, -20.32665214,\n", - " 13.65470057, -21.81612028, 5.30288097, 5.92310229,\n", - " 7.38953516]),\n", - " array([ 8.81486371e-02, 8.57021449e-01, 1.21288803e+00, -1.12476840e-02,\n", - " 6.49233883e-01, 1.64672032e-01, 7.42463452e-01, 2.53080481e+00,\n", - " 4.63153437e+00, -1.41255520e-01, -2.44119437e-01, 5.95007103e-01,\n", - " 1.60702303e+00, -2.67455760e+00, 2.85802575e+00, 3.41932331e+00,\n", - " -1.13601094e+01, 8.13133389e+00, 8.04002920e-01, 4.14565654e+01,\n", - " 1.22123683e+01, -2.35470049e+01, -2.49901414e+01, -1.93664172e+01,\n", - " 6.72650078e+00]),\n", - " array([-7.17194884e-02, 5.20237926e-01, 1.25437883e+00, -6.72139895e-01,\n", - " 5.64608717e-02, 5.80535200e-01, 4.56091014e-01, -8.12901895e+00,\n", - " 6.30184634e+00, 1.29233896e+01, -1.29923248e+00, 1.46264807e-01,\n", - " 4.85297534e-02, -3.45928761e+00, 8.98712413e-01, -7.88098328e+00,\n", - " -4.20658619e+01, -7.32595614e+00, -3.89744342e+00, -2.13196475e+02,\n", - " 3.34062395e+01, 2.61292903e+02, -2.11022610e+01, -8.97484592e+00,\n", - " -3.11698655e+01]),\n", - " array([-4.37081365e-01, 2.46307907e-01, 1.56633672e+00, -9.14522136e-01,\n", - " -1.36126871e-01, 3.80906465e-01, -5.38534022e-03, 1.53913761e+01,\n", - " 1.15223598e+02, -2.77542803e+01, 9.18312582e-01, 4.58295254e+00,\n", - " 3.00079799e+01, -5.97437634e+00, 1.71861717e+01, -1.76744803e+01,\n", - " 3.26177195e+02, -1.33352186e+02, -2.11024126e+01, 4.70407902e+02,\n", - " 2.17843503e+03, -8.13553398e+02, 4.43509013e+01, 8.87337547e+01,\n", - " 5.99189002e+02]),\n", - " array([-4.35371796e-01, 1.10911703e+01, -1.79580439e-01, -9.37654046e-01,\n", - " -1.45784841e-01, 3.14920824e-01, -1.94047456e-02, 2.22968190e+03,\n", - " -9.46737862e+02, -9.31663314e+02, -1.76932787e+01, -1.24874662e+02,\n", - " -2.94722413e+02, -1.27180158e+02, -2.82650462e+02, -2.05081941e+02,\n", - " 5.98049971e+03, -1.58724163e+04, -2.80309772e+00, 4.42858104e+04,\n", - " -2.12392292e+04, -1.80781807e+04, -3.72231826e+02, -2.58915230e+03,\n", - " -6.49460785e+03]),\n", - " array([-3.69749946e+03, -4.21224671e+03, 3.37653300e+03, -2.55544535e-01,\n", - " 2.13712875e-01, 6.12718656e-01, 7.16658668e-01, 1.18706856e+06,\n", - " 1.05506874e+06, 1.04206260e+06, -9.84266766e+03, 2.70417473e+04,\n", - " -2.86883233e+05, -1.88546674e+05, -9.24092119e+04, 1.96541350e+05,\n", - " -3.10404276e+07, 1.46610806e+07, -2.34128526e+03, 2.36967776e+07,\n", - " 2.11203095e+07, 2.08598852e+07, -1.96499488e+05, 5.43332439e+05,\n", - " -5.73177021e+06])],\n", - " [array([ 9.51382675e+01, 9.54447914e+01, 9.54790488e+01, 9.51947537e+01,\n", - " -9.04087045e-02, -8.84112238e-02, -2.02035681e-02, -1.20778235e-02,\n", - " -4.34182071e-03, -8.05589246e-02]),\n", - " array([-70.02387102, -71.8002623 , -70.99504382, -70.94952921,\n", - " 0.12012801, 0.23984258, 0.30772162, 0.28173833,\n", - " 0.22189178, 0.1219746 ]),\n", - " array([-1.76561574e+01, -1.78621603e+01, -1.72759244e+01, -1.82541104e+01,\n", - " 1.12744958e-02, 1.10414216e-01, 1.28879560e-01, 1.06813479e-01,\n", - " 7.58065148e-02, 3.35766173e-02]),\n", - " array([ 3.09026632e+00, 2.37496114e+00, 2.54852531e+00, 2.93585923e+00,\n", - " -1.87565727e-02, 4.52621346e-02, 6.28590682e-02, 5.43316938e-02,\n", - " 3.85745614e-02, 7.13061457e-04]),\n", - " array([ 4.19340244e+00, 3.68910430e+00, 3.80336101e+00, 4.07984146e+00,\n", - " -6.40195666e-04, 4.81811994e-02, 4.22909028e-02, 3.77546744e-02,\n", - " 2.79892550e-02, 7.28559217e-03]),\n", - " array([2.91449575e+00, 2.70600933e+00, 2.80948507e+00, 2.81035718e+00,\n", - " 6.88757575e-04, 3.96269089e-02, 2.77842184e-02, 2.45593323e-02,\n", - " 1.83693452e-02, 1.03028543e-02]),\n", - " array([ 2.65456196e+00, 2.53706658e+00, 2.58551936e+00, 2.60690439e+00,\n", - " -7.67696430e-04, 2.72729387e-02, 1.36390140e-02, 1.22883659e-02,\n", - " 9.28130028e-03, 7.53823406e-03]),\n", - " array([ 2.70428460e+00, 2.61693719e+00, 2.62521299e+00, 2.69668238e+00,\n", - " -6.56211675e-04, 2.05273712e-02, 3.33611954e-03, 3.42613114e-03,\n", - " 2.78779018e-03, 4.99839541e-03]),\n", - " array([ 2.71150582e+00, 2.64948989e+00, 2.63452665e+00, 2.72541110e+00,\n", - " 1.06991521e-03, 1.80037676e-02, -3.34092826e-03, -2.34588135e-03,\n", - " -1.42189771e-03, 3.92059494e-03]),\n", - " array([ 2.70092164, 2.65523011, 2.62409891, 2.72890056, 0.00316335,\n", - " 0.01749026, -0.00799196, -0.00634549, -0.00433209, 0.0036786 ]),\n", - " array([ 2.69889425, 2.65967933, 2.61445941, 2.73793847, 0.0061813 ,\n", - " 0.01862653, -0.01185529, -0.00962346, -0.00670212, 0.00394113]),\n", - " array([ 2.70359304, 2.66306216, 2.60462961, 2.75243451, 0.00958927,\n", - " 0.02166236, -0.01535564, -0.01256128, -0.00881241, 0.00470615]),\n", - " array([ 2.71312441, 2.6631759 , 2.59202445, 2.77151283, 0.01275492,\n", - " 0.02703063, -0.01866334, -0.01532816, -0.0107955 , 0.00601335]),\n", - " array([ 2.72681016, 2.65740231, 2.57340468, 2.79517435, 0.01561617,\n", - " 0.0356512 , -0.02192322, -0.0180609 , -0.01275717, 0.0080341 ]),\n", - " array([ 2.74617067, 2.64269936, 2.54625021, 2.82611765, 0.01647814,\n", - " 0.04918333, -0.02475173, -0.0204549 , -0.01448275, 0.0110011 ]),\n", - " array([ 2.78240428, 2.62306785, 2.51264515, 2.87970175, 0.01315496,\n", - " 0.0700661 , -0.02713535, -0.02253289, -0.01600121, 0.01495021]),\n", - " array([ 2.84666323, 2.60645762, 2.45673792, 2.96590026, 0.03046495,\n", - " 0.10131193, -0.0371604 , -0.03094774, -0.02210579, 0.02215801]),\n", - " array([ 2.87006372, 2.49322228, 2.32522926, 2.9840577 , 0.05350967,\n", - " 0.14704859, -0.04094036, -0.03395718, -0.02428181, 0.03570137]),\n", - " array([ 2.74105192, 2.07584353, 2.14420516, 2.82640147, -0.15302927,\n", - " 0.21798463, 0.05284388, 0.04364449, 0.0316475 , 0.03636098]),\n", - " array([ 3.11784238e+00, 2.24340069e+00, 2.12870941e+00, 3.31818044e+00,\n", - " -8.54610444e-02, 3.39997516e-01, -3.10399144e-03, -2.79623637e-03,\n", - " -1.35463319e-03, 3.95367551e-02]),\n", - " array([ 6.08373131, 5.12630941, 4.46754765, 6.62196579, 0.11950794,\n", - " 0.47742159, -0.14244726, -0.11724362, -0.08401462, 0.08168448]),\n", - " array([ 8.00024898, 8.75274428, 8.56249374, 8.22343395, -0.04359842,\n", - " 0.64906559, -0.01481111, 0.01040867, 0.01465522, 0.17768602]),\n", - " array([-35.2821004 , -53.40481728, -56.0564881 , -34.2376544 ,\n", - " 1.61353041, 1.04025586, -0.60337177, -0.50674173,\n", - " -0.33152462, 0.11826687]),\n", - " array([63.46457546, 74.00404397, 91.26618784, 54.71895839, -8.53180324,\n", - " 0.54604778, 5.26793635, 4.67794644, 3.6079323 , -0.62450635]),\n", - " array([-27.1435977 , 5.22710757, -24.19076202, -2.05782652,\n", - " 4.13332421, -7.53932407, -2.46854517, -1.9875779 ,\n", - " -1.31675771, -2.64179762]),\n", - " array([ -6.90671985, -35.9055569 , -1.1384089 , -47.89154557,\n", - " 6.5985733 , 0.92346971, -3.03486627, -2.93858154,\n", - " -2.39389461, 3.88533061]),\n", - " array([33.48716997, 37.2068011 , 21.85151941, 50.68398882, -1.88115105,\n", - " -1.03797381, 1.00483246, 0.81618428, 0.49128764, -1.68391803]),\n", - " array([-43.24487739, -28.72246877, -28.80882483, -45.39320135,\n", - " 2.02376196, 0.47290045, -0.75531558, -0.44740929,\n", - " -0.22447397, 1.16752352]),\n", - " array([47.44298821, 24.78813167, 36.492302 , 39.85430075, -3.83754988,\n", - " -0.36780023, 2.93230743, 2.33236301, 1.62090633, -0.29626034]),\n", - " array([-4.44966390e+01, -2.77057730e+01, -3.28177643e+01, -3.97095746e+01,\n", - " 1.29058582e-01, 3.74451723e-01, -1.28331573e-01, -3.95096188e-02,\n", - " 2.30169942e-02, -3.60643915e-01]),\n", - " array([51.02355601, 43.63758782, 34.4775619 , 54.41720489, 5.79351319,\n", - " 0.31818708, -4.71765285, -3.66363949, -2.55867512, 0.5522248 ]),\n", - " array([-4.14198733e+01, -3.69973750e+01, -2.96756171e+01, -4.52376537e+01,\n", - " -3.53639904e+00, 6.03583001e-02, 3.80899111e+00, 2.87045975e+00,\n", - " 1.95701611e+00, -2.43533330e-02]),\n", - " array([48.63865467, 38.62723337, 39.96464533, 51.24482843, -3.89125375,\n", - " 0.16865277, 2.50716522, 2.23004862, 1.64012621, -0.46628211]),\n", - " array([-30.70420479, -28.17209415, -33.33826386, -39.41010705,\n", - " 13.7852292 , 0.27563473, -10.37473856, -8.59912157,\n", - " -6.16918538, 1.13033844]),\n", - " array([ 25.79912978, 36.69414433, 36.35355778, 44.36706492,\n", - " -18.34863943, -0.99884329, 13.55450802, 10.9094032 ,\n", - " 7.69295302, -2.29256795]),\n", - " array([-34.71590512, -38.25919313, -44.32949341, -43.42852479,\n", - " 14.76521495, -0.25089212, -9.65183011, -7.01626167,\n", - " -4.638893 , 1.69274078]),\n", - " array([68.78433243, 69.08128127, 87.9543492 , 55.05822546, -5.23668897,\n", - " -5.75081351, -1.25204253, -2.82099197, -2.75360048, -1.8116989 ]),\n", - " array([-99.4385295 , -71.11364114, -89.08080045, -78.95751368,\n", - " -2.32221153, 1.51264908, 8.84583986, 9.66312642,\n", - " 7.91412602, 1.84610654]),\n", - " array([66.13578285, 17.77527654, 47.08565701, 33.3059726 , 3.70692322,\n", - " -1.61311281, -7.38892511, -7.99908013, -6.36877604, -0.10170829]),\n", - " array([ 29.22649742, 62.81680152, 56.96115153, 47.83337564,\n", - " -12.54839643, -3.0214439 , 9.77199128, 8.82084224,\n", - " 6.44673972, -0.94036539]),\n", - " array([ -2.20770687, -81.94987581, -47.76968533, -53.83106259,\n", - " 17.67502553, -0.53647182, -16.55947807, -15.84421387,\n", - " -11.9863268 , 2.82099635]),\n", - " array([-41.46281037, 138.31059332, 61.3675991 , 57.59836954,\n", - " -22.7756343 , -4.21646748, 22.77929971, 23.24640231,\n", - " 18.16251809, -4.45760471]),\n", - " array([ 39.20879523, -98.38811346, -22.57967597, -65.74906803,\n", - " 28.94920848, -6.79002307, -23.60341769, -22.60462754,\n", - " -16.9997745 , 2.67045546]),\n", - " array([ -0.37968177, 44.99598476, 138.83368551, -64.4105193 ,\n", - " -30.61311926, -31.45707746, 14.72314159, 13.61230793,\n", - " 9.94716573, 0.71093857]),\n", - " array([143.72037329, -56.41343967, 73.6923721 , -19.53644702,\n", - " 34.84195902, -13.53782953, -11.65902186, -15.70930379,\n", - " -13.69984726, 6.64954999]),\n", - " array([ 18.04122303, -224.30150689, 44.87054542, -197.66543894,\n", - " -56.7367418 , -13.45278651, 46.04162915, 36.81108562,\n", - " 26.80569562, -1.57731813]),\n", - " array([-237.05073142, 227.77493498, -83.883216 , -303.00727897,\n", - " 365.61572264, -72.39286906, -266.50599807, -192.62330823,\n", - " -131.30849181, 11.20277466]),\n", - " array([ -473.19830439, 489.28812697, 1984.10239617, -166.26820898,\n", - " -1789.64683411, -1093.96483919, 181.99874164, 129.08781274,\n", - " 132.5698816 , -23.56955846]),\n", - " array([-24632.75402335, 52176.68286695, -14864.79565776, 2705.73754142,\n", - " 39500.25555513, 1264.78674662, -58865.81190584, -60436.49857178,\n", - " -43190.57961228, 2850.58693808])],\n", - " False)" - ] - }, - "execution_count": 30, - "metadata": {}, - "output_type": "execute_result" } ], "source": [ @@ -672,7 +174,7 @@ }, { "cell_type": "code", - "execution_count": 31, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -681,20 +183,9 @@ }, { "cell_type": "code", - "execution_count": 17, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "6" - ] - }, - "execution_count": 17, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "robot.nv" ] @@ -712,31 +203,7 @@ "cell_type": "code", "execution_count": null, "metadata": {}, - "outputs": [ - { - "ename": "AttributeError", - "evalue": "PlotUAM instance has no attribute 'plotActuation'", - "output_type": "error", - "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mAttributeError\u001b[0m Traceback (most recent call last)", - "\u001b[0;32m<ipython-input-17-7e2e2bd56186>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m 5\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 6\u001b[0m \u001b[0mfig\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0maxs\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mpltUAM\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mplotMotorForces\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 7\u001b[0;31m \u001b[0mfig\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0maxs\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mpltUAM\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mplotActuation\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m", - "\u001b[0;31mAttributeError\u001b[0m: PlotUAM instance has no attribute 'plotActuation'" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "<matplotlib.figure.Figure at 0x7fd9fb7fa550>" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], + "outputs": [], "source": [ "distanceRotorCOG = 0.1525\n", "cf = 6.6e-5\n", diff --git a/examples/notebooks/kinton/kinton_flying_ee.ipynb b/examples/notebooks/kinton/kinton_flying_ee.ipynb index 63b5c5fc9008710fc84a3e43237ad15965c9e2cb..2b178b5473fadce6ab482ef73e7011e67c501258 100644 --- a/examples/notebooks/kinton/kinton_flying_ee.ipynb +++ b/examples/notebooks/kinton/kinton_flying_ee.ipynb @@ -520,7 +520,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.16" + "version": "2.7.12" } }, "nbformat": 4, diff --git a/examples/notebooks/kinton/quadcopter_mission.ipynb b/examples/notebooks/kinton/quadcopter_mission.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..50c6d619b0d5a1187642055fd3882eb66c6e00ca --- /dev/null +++ b/examples/notebooks/kinton/quadcopter_mission.ipynb @@ -0,0 +1,584 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from crocoddyl import *\n", + "import pinocchio as pin\n", + "import numpy as np\n", + "from crocoddyl.diagnostic import displayTrajectory" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "# LOAD ROBOT\n", + "robot = loadHector()\n", + "robot.initViewer(loadModel=True)\n", + "robot.display(robot.q0)\n", + "\n", + "robot.framesForwardKinematics(robot.q0)\n", + "\n", + "rmodel = robot.model" + ] + }, + { + "cell_type": "code", + "execution_count": 69, + "metadata": {}, + "outputs": [], + "source": [ + "def uavPlacementModel(targetPos, targetQuat, integrationStep, frameName):\n", + " # ACTUATION MODEL\n", + " distanceRotorCOG = 0.1525\n", + " cf = 6.6e-5\n", + " cm = 1e-6\n", + " actModel = ActuationModelUAM(robot.model, '+', distanceRotorCOG, cf, cm)\n", + "\n", + " # COST MODEL\n", + " # Create a cost model per the running and terminal action model.\n", + " runningCostModel = CostModelSum(rmodel, actModel.nu)\n", + " terminalCostModel = CostModelSum(rmodel, actModel.nu)\n", + "\n", + " state = StatePinocchio(rmodel)\n", + " SE3ref = pin.SE3()\n", + " SE3ref.translation = targetPos.reshape(3,1)\n", + " SE3ref.rotation = targetQuat.matrix()\n", + "\n", + " wBasePos = [0.1]\n", + " wBaseOri = [100]\n", + " wBaseVel = [100]\n", + " wBaseRate = [10]\n", + " \n", + " stateWeights = np.array(wBasePos * 3 + wBaseOri * 3 + wBaseVel * robot.model.nv)\n", + " controlWeights = np.array([1]*4)\n", + " \n", + " goalTrackingCost = CostModelFramePlacement(rmodel,\n", + " frame=rmodel.getFrameId(frameName),\n", + " ref=SE3ref,\n", + " nu=actModel.nu)\n", + " xRegCost = CostModelState(rmodel, \n", + " state, \n", + " ref=state.zero(), \n", + " nu=actModel.nu,\n", + " activation=ActivationModelWeightedQuad(stateWeights))\n", + " uRegCost = CostModelControl(rmodel, \n", + " nu=robot.\n", + " model.nv-2,\n", + " activation = ActivationModelWeightedQuad(controlWeights))\n", + " uLimCost = CostModelControl(rmodel, \n", + " nu=robot.\n", + " model.nv-2,\n", + " activation = ActivationModelInequality(np.array([0.1, 0.1, 0.1, 0.1]), \n", + " np.array([5, 5, 5, 5])))\n", + "\n", + " # Then let's add the running and terminal cost functions\n", + " runningCostModel.addCost(name=\"pos\", weight=0.01, cost=goalTrackingCost)\n", + " runningCostModel.addCost(name=\"regx\", weight=1e-6, cost=xRegCost)\n", + " runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n", + " runningCostModel.addCost(name=\"limu\", weight=1e-4, cost=uLimCost)\n", + " terminalCostModel.addCost(name=\"pos\", weight=50, cost=goalTrackingCost)\n", + "\n", + " # DIFFERENTIAL ACTION MODEL\n", + " runningDmodel = DifferentialActionModelActuated(rmodel, actModel, runningCostModel)\n", + " terminalDmodel = DifferentialActionModelActuated(rmodel, actModel, terminalCostModel)\n", + " runningModel = IntegratedActionModelEuler(runningDmodel)\n", + " runningModel.timeStep = integrationStep \n", + " terminalModel = IntegratedActionModelEuler(terminalDmodel)\n", + " terminalModel.timeStep = integrationStep \n", + " \n", + " return runningModel,terminalModel " + ] + }, + { + "cell_type": "code", + "execution_count": 70, + "metadata": { + "scrolled": true + }, + "outputs": [], + "source": [ + "# DEFINING THE SHOOTING PROBLEM & SOLVING\n", + "\n", + "dt = 3e-2\n", + "T = 33\n", + "\n", + "# DEFINE POSITION WAYPOINTS\n", + "target_pos = [np.array([0,0,1])]\n", + "target_pos += [np.array([0,1,1])]\n", + "quat = pin.Quaternion(1, 0, 0, 0)\n", + "quat.normalize()\n", + "target_quat = [quat]*2\n", + "\n", + "# Plot goal frame\n", + "for i in range(0,len(target_pos)):\n", + " robot.viewer.gui.addXYZaxis('world/wp%i' % i, [1., 0., 0., 1.], .03, 0.5)\n", + " robot.viewer.gui.applyConfiguration('world/wp%i' % i, \n", + " target_pos[i].tolist() + [target_quat[i][0], target_quat[i][1], target_quat[i][2], target_quat[i][3]])\n", + " \n", + "robot.viewer.gui.refresh()" + ] + }, + { + "cell_type": "code", + "execution_count": 71, + "metadata": { + "scrolled": true + }, + "outputs": [], + "source": [ + "models = []\n", + "# len(target_pos)\n", + "for i in range(1, 2):\n", + " runningModel, terminalModel = uavPlacementModel(target_pos[i], target_quat[i], dt, 'base_link')\n", + " models += [runningModel]*(T-1) + [terminalModel]\n", + "\n", + " \n", + "# From ground to 1st waypoint\n", + "q0 = robot.q0\n", + "x0 = np.hstack([m2a(q0), np.zeros(robot.model.nv)])\n", + "\n", + "problem = ShootingProblem(x0, models[:-1], models[-1])\n", + "\n", + "# Creating the DDP solver for this OC problem, defining a logger\n", + "ddp = SolverFDDP(problem)\n", + "ddp.callback = [CallbackDDPVerbose()]\n", + "ddp.callback.append(CallbackDDPLogger())\n", + "\n", + "# From 1st waypoint to 2nd waypoint\n", + "# x0 = np.array([ 3.64921977e-11, -2.33702527e-10, 9.99972616e-01, 7.55260190e-13, \n", + "# 1.18488377e-13, 5.00281541e-18, 1.00000000e+00, 7.78469510e-08,\n", + "# -4.97668391e-07, -4.04832071e-01, 1.15972591e-06, 1.81076620e-07, -9.47254507e-15])\n", + "\n", + "us0 = [m.differential.quasiStatic(d.differential, problem.initialState)\n", + " for m, d in zip(ddp.problem.runningModels, ddp.problem.runningDatas)]\n", + "\n", + "xs0 = [problem.initialState]\n", + "N = len(problem.runningModels)\n", + "x_goal = target_pos[1]\n", + "x_start = problem.initialState\n", + "for i in range(0, N):\n", + " alpha = float(i)/float(N) \n", + " x_curr = x_start[:3] + alpha*(x_goal - x_start[:3])\n", + " x_curr = np.append(x_curr, np.array([0,0,0,1] + [0]*rmodel.nv))\n", + " xs0 = xs0 + [x_curr]" + ] + }, + { + "cell_type": "code", + "execution_count": 72, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 0 1.49063e-01 1.43562e-04 1.11205e+00 1.00000e-09 1.00000e-09 0.5000 0\n", + " 1 1.44419e-01 4.04310e-05 2.98015e-01 1.00000e-09 1.00000e-09 0.5000 0\n", + " 2 1.41430e-01 1.70531e-05 1.74841e-01 1.00000e-09 1.00000e-09 0.1250 0\n", + " 3 1.62549e-01 1.17043e-05 2.15751e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 4 1.53148e-01 1.25240e-05 1.51471e-01 1.00000e-09 1.00000e-09 0.1250 1\n", + " 5 1.51509e-01 4.15297e-06 1.60413e-02 1.00000e-09 1.00000e-09 0.2500 1\n", + " 6 1.49708e-01 4.91016e-06 2.97482e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 7 1.48270e-01 3.41466e-06 1.19152e-02 1.00000e-09 1.00000e-09 0.2500 1\n", + " 8 1.46923e-01 3.69564e-06 2.10745e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 9 1.45710e-01 2.77103e-06 9.21471e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 10 1.44663e-01 2.94523e-06 1.58120e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 11 1.44341e-01 2.26251e-06 7.35190e-03 1.00000e-09 1.00000e-09 0.5000 1\n", + " 12 1.42242e-01 4.78284e-06 5.45618e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 13 1.41447e-01 2.10589e-06 1.47243e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 14 1.41030e-01 1.51869e-06 5.67241e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 15 1.40383e-01 1.78221e-06 1.30769e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 16 1.40183e-01 1.29005e-06 5.40093e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 17 1.39548e-01 1.69022e-06 1.47019e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 18 1.39193e-01 1.14072e-06 5.73348e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 19 1.38922e-01 8.96443e-07 3.15628e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 20 1.38557e-01 1.10719e-06 7.48324e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 21 1.38318e-01 7.92714e-07 3.56071e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 22 1.38086e-01 6.91736e-07 2.24165e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 23 1.37835e-01 7.88126e-07 5.19253e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 24 1.37652e-01 6.24253e-07 2.70150e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 25 1.37471e-01 5.21580e-07 1.70699e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 26 1.37281e-01 6.23285e-07 3.91068e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 27 1.37232e-01 4.67481e-07 2.05004e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 28 1.36994e-01 7.15274e-07 6.35670e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 29 1.36852e-01 4.54366e-07 2.82905e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 30 1.36803e-01 3.66277e-07 1.51369e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 31 1.36575e-01 6.57583e-07 5.23703e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 32 1.36425e-01 4.37883e-07 2.51651e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 33 1.36320e-01 3.51611e-07 1.45836e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 34 1.36159e-01 4.68814e-07 3.83685e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 35 1.36049e-01 3.29411e-07 1.87932e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 36 1.35973e-01 2.69452e-07 1.09215e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 37 1.35851e-01 3.54592e-07 2.92419e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 38 1.35768e-01 2.54240e-07 1.43367e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 39 1.35711e-01 2.04975e-07 8.33967e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 40 1.35617e-01 2.74558e-07 2.23762e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 41 1.35553e-01 1.93820e-07 1.09350e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 42 1.35510e-01 1.58519e-07 6.31795e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 43 1.35439e-01 2.09030e-07 1.69837e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 44 1.35391e-01 1.50421e-07 8.30555e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 45 1.35359e-01 1.21901e-07 4.83961e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 46 1.35308e-01 1.52510e-07 1.27914e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 47 1.35273e-01 1.03990e-07 6.10453e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 48 1.35253e-01 8.48426e-08 3.44008e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 49 1.35215e-01 1.11569e-07 9.59001e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 50 1.35189e-01 7.99990e-08 4.61242e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 51 1.35177e-01 6.28589e-08 2.54978e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 52 1.35149e-01 8.99001e-08 7.35389e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 53 1.35130e-01 5.96259e-08 3.48775e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 54 1.35121e-01 4.94345e-08 1.94297e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 55 1.35099e-01 6.64752e-08 5.68975e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 56 1.35084e-01 4.83036e-08 2.71611e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 57 1.35077e-01 3.73795e-08 1.52546e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 58 1.35060e-01 5.51920e-08 4.58442e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 59 1.35048e-01 3.62546e-08 2.12275e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 60 1.35043e-01 3.00242e-08 1.16329e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 61 1.35029e-01 4.01583e-08 3.36668e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 62 1.35024e-01 4.40004e-08 2.24277e-04 1.00000e-09 1.00000e-09 0.2500 1\n", + " 63 1.35002e-01 5.76909e-08 6.39571e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 64 1.34989e-01 3.54257e-08 2.83648e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 65 1.34980e-01 2.52395e-08 1.43069e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 66 1.34974e-01 2.07059e-08 8.54626e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 67 1.34964e-01 2.72541e-08 2.25673e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 68 1.34958e-01 1.95973e-08 1.10304e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 69 1.34953e-01 1.58079e-08 6.33059e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 70 1.34946e-01 2.09694e-08 1.66354e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 71 1.34941e-01 1.50800e-08 8.45972e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 72 1.34937e-01 1.25339e-08 5.13837e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 73 1.34932e-01 1.71805e-08 1.47899e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 74 1.34927e-01 1.20124e-08 6.82963e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 75 1.34924e-01 9.63737e-09 3.80106e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 76 1.34920e-01 1.26502e-08 9.78031e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 77 1.34917e-01 9.11001e-09 4.93212e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 78 1.34914e-01 7.63467e-09 2.97540e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 79 1.34911e-01 9.73672e-09 7.59754e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 80 1.34909e-01 7.23795e-09 3.85144e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 81 1.34907e-01 5.94691e-09 2.33830e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 82 1.34904e-01 7.71660e-09 5.90896e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 83 1.34902e-01 5.58616e-09 3.00304e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 84 1.34901e-01 4.69765e-09 1.82013e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 85 1.34899e-01 6.06763e-09 4.85759e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 86 1.34897e-01 4.55942e-09 2.55998e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 87 1.34897e-01 3.74121e-09 1.61305e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 88 1.34895e-01 5.65204e-09 5.29829e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 89 1.34893e-01 3.69978e-09 2.34646e-05 1.00000e-09 1.00000e-09 0.1250 1\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 90 1.34893e-01 2.91875e-09 1.14777e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 91 1.34891e-01 3.81864e-09 3.11718e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 92 1.34890e-01 2.86724e-09 1.65333e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 93 1.34890e-01 2.34551e-09 1.04444e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 94 1.34889e-01 3.66078e-09 3.55623e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 95 1.34888e-01 2.41271e-09 1.66945e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 96 1.34888e-01 1.87561e-09 8.15072e-06 1.00000e-09 1.00000e-09 0.2500 1\n", + " 97 1.34887e-01 2.60268e-09 2.36205e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 98 1.34886e-01 1.85305e-09 1.14409e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 99 1.34885e-01 1.50861e-09 7.35515e-06 1.00000e-09 1.00000e-09 0.1250 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 100 1.34885e-01 1.35726e-09 5.50366e-06 1.00000e-09 1.00000e-09 0.2500 1\n", + " 101 1.34884e-01 1.62271e-09 1.25570e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 102 1.34884e-01 1.19312e-09 5.41702e-06 1.00000e-09 1.00000e-09 0.2500 1\n", + " 103 1.34884e-01 1.75123e-09 1.70159e-05 1.00000e-09 1.00000e-09 0.1250 1\n", + " 104 1.34883e-01 1.25484e-09 8.85495e-06 1.00000e-09 1.00000e-09 0.1250 1\n", + " 105 1.34883e-01 1.01858e-09 5.97769e-06 1.00000e-09 1.00000e-09 0.1250 1\n", + " 106 1.34883e-01 9.14728e-10 4.59803e-06 1.00000e-09 1.00000e-09 0.1250 1\n" + ] + }, + { + "data": { + "text/plain": [ + "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0.]),\n", + " array([-6.20464074e-07, 5.53926180e-04, 1.10871654e-02, -4.98986956e-02,\n", + " -1.09026993e-04, -1.59607050e-03, 9.98753003e-01, 0.00000000e+00,\n", + " 0.00000000e+00, 3.70186867e-01, -3.32796314e+00, -7.27148899e-03,\n", + " -1.06448951e-01]),\n", + " array([-1.21004983e-06, 3.75061235e-03, 3.33491575e-02, -1.02684987e-01,\n", + " -6.86382934e-05, -1.33111686e-03, 9.94713032e-01, -3.02161576e-05,\n", + " -7.62540239e-03, 7.49989401e-01, -3.52978846e+00, -3.84003489e-03,\n", + " 1.77379963e-02]),\n", + " array([-1.58431907e-07, 1.11048995e-02, 6.60993206e-02, -1.41608622e-01,\n", + " -6.52544898e-05, -9.89373737e-04, 9.89922227e-01, -6.85144909e-05,\n", + " -2.69237213e-02, 1.11882089e+00, -2.61465513e+00, -5.59254805e-03,\n", + " 2.24443096e-02]),\n", + " array([ 2.62553211e-06, 2.33727013e-02, 1.08232498e-01, -1.62518146e-01,\n", + " -8.09875740e-05, -7.19330240e-04, 9.86705289e-01, -1.94180777e-05,\n", + " -3.21727925e-02, 1.46251661e+00, -1.41039289e+00, -4.98118965e-03,\n", + " 1.75530300e-02]),\n", + " array([ 6.38871615e-06, 4.07198129e-02, 1.58633069e-01, -1.67265945e-01,\n", + " -9.23356100e-05, -5.18647444e-04, 9.85911673e-01, 6.63468421e-05,\n", + " 3.31925093e-04, 1.77675162e+00, -3.20909981e-01, -3.15276364e-03,\n", + " 1.30656609e-02]),\n", + " array([ 1.01135256e-05, 6.28415045e-02, 2.16077892e-01, -1.59708282e-01,\n", + " -9.44843439e-05, -3.72585580e-04, 9.87164179e-01, 1.29881967e-04,\n", + " 8.02922518e-02, 2.05035199e+00, 5.10718599e-01, -1.50096297e-03,\n", + " 9.57319067e-03]),\n", + " array([ 1.32518520e-05, 8.92463726e-02, 2.79511995e-01, -1.44137526e-01,\n", + " -8.65482015e-05, -2.67471108e-04, 9.89557626e-01, 1.55342345e-04,\n", + " 2.04504453e-01, 2.28128940e+00, 1.05025362e+00, -1.95060997e-04,\n", + " 6.96384007e-03]),\n", + " array([ 1.53207706e-05, 1.19410453e-01, 3.48246795e-01, -1.24071516e-01,\n", + " -7.40299160e-05, -1.91449890e-04, 9.92273257e-01, 1.38313765e-04,\n", + " 3.60335805e-01, 2.47616569e+00, 1.34995230e+00, 4.68843072e-04,\n", + " 5.06844013e-03]),\n", + " array([ 1.63559352e-05, 1.52710869e-01, 4.21394134e-01, -1.02336492e-01,\n", + " -5.85181397e-05, -1.35886302e-04, 9.94749828e-01, 1.01057364e-04,\n", + " 5.33081165e-01, 2.62566889e+00, 1.45840678e+00, 8.56239667e-04,\n", + " 3.72855932e-03]),\n", + " array([ 1.63402790e-05, 1.88574601e-01, 4.98401593e-01, -8.05954752e-02,\n", + " -4.34434097e-05, -9.43398357e-05, 9.96746888e-01, 5.07919623e-05,\n", + " 7.07878962e-01, 2.74196185e+00, 1.45553195e+00, 9.21075580e-04,\n", + " 2.79156608e-03]),\n", + " array([ 1.55488996e-05, 2.26441294e-01, 5.78876416e-01, -5.95364756e-02,\n", + " -2.84305363e-05, -6.21195385e-05, 9.98226128e-01, 4.34511991e-06,\n", + " 8.74893522e-01, 2.83281645e+00, 1.40741870e+00, 9.61284105e-04,\n", + " 2.17016967e-03]),\n", + " array([ 1.76114165e-05, 2.65634813e-01, 6.54916635e-01, -4.69710518e-02,\n", + " -2.76065713e-05, -1.55265606e-04, 9.98896239e-01, -3.92704959e-05,\n", + " 1.02948329e+00, 2.65931919e+00, 8.38890648e-01, 4.77859396e-04,\n", + " -6.21665719e-03]),\n", + " array([ 1.27766185e-05, 3.05037950e-01, 7.22263163e-01, -3.54940241e-02,\n", + " -1.94025469e-05, -3.83842017e-05, 9.99369888e-01, -2.89916203e-04,\n", + " 1.12402627e+00, 2.34552488e+00, 7.65790813e-01, 3.00005943e-04,\n", + " 7.79313450e-03]),\n", + " array([ 1.13109338e-05, 3.44607761e-01, 7.80818114e-01, -2.48967175e-02,\n", + " -1.20854262e-05, -2.05306030e-05, 9.99690028e-01, -6.04507658e-05,\n", + " 1.19879040e+00, 2.02793021e+00, 7.06812721e-01, 4.72795169e-04,\n", + " 1.19393814e-03]),\n", + " array([ 1.00017963e-05, 3.84315036e-01, 8.30555997e-01, -1.49814781e-02,\n", + " -8.41615864e-06, -1.39964373e-05, 9.99887771e-01, -5.36883234e-05,\n", + " 1.25644107e+00, 1.70941111e+00, 6.61150115e-01, 2.47431163e-04,\n", + " 4.33855308e-04]),\n", + " array([ 8.81580561e-06, 4.24130931e-01, 8.71423168e-01, -5.40996865e-03,\n", + " -3.09766190e-06, -9.90363937e-06, 9.99985366e-01, -5.51003789e-05,\n", + " 1.29916350e+00, 1.38903938e+00, 6.38136232e-01, 3.59430295e-04,\n", + " 2.72859377e-04]),\n", + " array([ 7.60754973e-06, 4.64038413e-01, 9.03512788e-01, 4.16748778e-03,\n", + " -6.93569784e-07, -8.95526306e-06, 9.99991316e-01, -6.12983889e-05,\n", + " 1.32893965e+00, 1.07132240e+00, 6.38499658e-01, 1.66255632e-04,\n", + " 6.21182630e-05]),\n", + " array([ 7.34143840e-06, 5.04028910e-01, 9.26899897e-01, 1.40357509e-02,\n", + " 3.34583332e-06, -3.10905624e-05, 9.99901494e-01, -6.45515122e-05,\n", + " 1.34700786e+00, 7.55188870e-01, 6.57914124e-01, 2.69033036e-04,\n", + " -1.47732998e-03]),\n", + " array([ 8.41566155e-06, 5.44100799e-01, 9.41654091e-01, 2.43680710e-02,\n", + " 6.53710360e-06, -8.73956797e-05, 9.99703051e-01, -1.28119871e-04,\n", + " 1.35365271e+00, 4.40163300e-01, 6.88951447e-01, 1.81508092e-04,\n", + " -3.75446431e-03]),\n", + " array([ 4.16016539e-06, 5.84230188e-01, 9.48170701e-01, 3.64587548e-02,\n", + " 7.31969077e-06, -1.20033899e-05, 9.99335158e-01, -2.77883774e-04,\n", + " 1.34841144e+00, 1.35493125e-01, 8.06423515e-01, 2.45245843e-04,\n", + " 5.02663711e-03]),\n", + " array([ 3.35784522e-06, 6.24036472e-01, 9.51038800e-01, 4.76935243e-02,\n", + " 9.74965896e-06, -2.07479854e-05, 9.98862016e-01, -7.09783041e-05,\n", + " 1.33024407e+00, -1.62980997e-02, 7.49652488e-01, 1.49860102e-04,\n", + " -5.83400265e-04]),\n", + " array([ 1.48631122e-06, 6.62919796e-01, 9.54708809e-01, 5.46510470e-02,\n", + " 9.42666782e-06, 1.97636232e-06, 9.98505515e-01, -8.78724087e-05,\n", + " 1.30183707e+00, -1.07840511e-02, 4.64444276e-01, 6.06012236e-05,\n", + " 1.51830089e-03]),\n", + " array([ 6.67436875e-07, 7.00576332e-01, 9.60669522e-01, 5.73863128e-02,\n", + " 9.33338306e-06, 3.25907472e-06, 9.98352048e-01, -2.30787217e-05,\n", + " 1.26956729e+00, 5.70328797e-02, 1.82637897e-01, -1.80020037e-06,\n", + " 8.74655270e-05]),\n", + " array([ 2.19577607e-06, 7.36933916e-01, 9.69130652e-01, 5.67070961e-02,\n", + " 1.17631082e-05, -5.28756585e-05, 9.98390856e-01, -1.43698481e-05,\n", + " 1.23615786e+00, 1.42155148e-01, -4.53549327e-02, -5.29195319e-05,\n", + " -3.74587527e-03]),\n", + " array([ 2.37850144e-06, 7.72028951e-01, 9.80066240e-01, 5.26257637e-02,\n", + " 1.10450062e-05, -6.80196740e-05, 9.98614302e-01, -1.44381462e-04,\n", + " 1.20264035e+00, 2.34631196e-01, -2.72496467e-01, -1.19610408e-04,\n", + " -1.00767743e-03]),\n", + " array([ 2.89746764e-06, 8.06117651e-01, 9.91878856e-01, 4.68304681e-02,\n", + " 9.95450001e-06, -8.92084366e-05, 9.98902848e-01, -1.71296711e-04,\n", + " 1.16978966e+00, 2.78936225e-01, -3.86832152e-01, -1.73431040e-04,\n", + " -1.40976758e-03]),\n", + " array([ 3.76173037e-06, 8.39453891e-01, 1.00289750e+00, 4.04821634e-02,\n", + " 8.71593618e-06, -1.18446826e-04, 9.99180254e-01, -2.11007602e-04,\n", + " 1.13901843e+00, 2.68959285e-01, -4.23624870e-01, -2.11703837e-04,\n", + " -1.94579678e-03]),\n", + " array([ 5.01237094e-06, 8.72243898e-01, 1.01165894e+00, 3.43779100e-02,\n", + " 7.49432994e-06, -1.58434859e-04, 9.99408892e-01, -2.67840041e-04,\n", + " 1.11179202e+00, 2.09465937e-01, -4.07236185e-01, -2.37630089e-04,\n", + " -2.66214474e-03]),\n", + " array([ 6.73307980e-06, 9.04646363e-01, 1.01690996e+00, 2.90397556e-02,\n", + " 6.40836197e-06, -2.12885278e-04, 9.99578235e-01, -3.47524858e-04,\n", + " 1.08901006e+00, 1.06220636e-01, -3.56056362e-01, -2.53616972e-04,\n", + " -3.62628896e-03]),\n", + " array([ 9.06644921e-06, 9.36788817e-01, 1.01742518e+00, 2.47962404e-02,\n", + " 5.52206399e-06, -2.87069040e-04, 9.99692485e-01, -4.57779455e-04,\n", + " 1.07078981e+00, -4.05111564e-02, -2.83003688e-01, -2.62955227e-04,\n", + " -4.94198869e-03]),\n", + " array([ 1.68888857e-05, 9.68779022e-01, 1.01165169e+00, 2.04637286e-02,\n", + " 8.00355080e-06, -5.35309183e-04, 9.99790453e-01, -6.09414889e-04,\n", + " 1.05654311e+00, -2.40503360e-01, -2.88908111e-01, -3.27932332e-04,\n", + " -1.65481278e-02]),\n", + " array([-7.53894460e-08, 1.00041937e+00, 1.00000547e+00, 2.15730341e-06,\n", + " 5.63587538e-08, 3.34392998e-07, 1.00000000e+00, -1.12513759e-03,\n", + " 1.04658489e+00, -4.09739635e-01, -1.36420005e+00, -5.29317372e-04,\n", + " 3.57119853e-02])],\n", + " [array([ 8.207219 , 3.96942747, 8.18890915, 12.34934778]),\n", + " array([8.26409957, 8.04752555, 8.2488596 , 8.55567614]),\n", + " array([8.09483381, 9.24861322, 8.09464155, 6.94428206]),\n", + " array([7.73152087, 9.24867302, 7.73701618, 6.2163097 ]),\n", + " array([7.31313789, 8.68631782, 7.31941077, 5.94297002]),\n", + " array([6.78559018, 7.83357484, 6.79003211, 5.73950959]),\n", + " array([6.29414536, 6.97395962, 6.29710408, 5.6153937 ]),\n", + " array([5.94949498, 6.32672117, 5.95067369, 5.57207018]),\n", + " array([5.53055767, 5.66687403, 5.53107192, 5.39378192]),\n", + " array([5.2651881 , 5.26112666, 5.2649848 , 5.26836536]),\n", + " array([5.07420474, 5.01331735, 5.07403208, 5.13446792]),\n", + " array([1.918109 , 1.19856412, 1.91668582, 2.63013627]),\n", + " array([ 0.06046991, -0.026522 , 0.06037362, 0.15754598]),\n", + " array([ 0.02317576, -0.05345985, 0.02320856, 0.09504876]),\n", + " array([ 0.01073596, -0.04734234, 0.0101116 , 0.06763757]),\n", + " array([-0.01589311, -0.04479511, -0.01563042, 0.01315459]),\n", + " array([0.01797556, 0.01810747, 0.0174774 , 0.01719235]),\n", + " array([0.04461027, 0.06862213, 0.04486639, 0.01973586]),\n", + " array([0.07120175, 0.10937344, 0.07104688, 0.03122047]),\n", + " array([0.21065877, 0.3619159 , 0.21099363, 0.06611743]),\n", + " array([2.1472105 , 2.07343985, 2.14669706, 2.21639107]),\n", + " array([4.04167157, 3.68325573, 4.04147629, 4.40141937]),\n", + " array([4.65904011, 4.30361905, 4.65883544, 5.01321675]),\n", + " array([4.73257733, 4.44407294, 4.73244754, 5.01816636]),\n", + " array([4.71616176, 4.43109204, 4.71598238, 5.00304186]),\n", + " array([4.02674082, 3.88256721, 4.02658679, 4.17046821]),\n", + " array([3.31672851, 3.27014456, 3.31659538, 3.36278981]),\n", + " array([2.70022723, 2.72054017, 2.70010638, 2.6792729 ]),\n", + " array([2.1760523 , 2.24008158, 2.17593896, 2.11120907]),\n", + " array([1.66732715, 1.75876838, 1.6672166 , 1.57481929]),\n", + " array([1.04665814, 1.03487857, 1.04640025, 1.04974602]),\n", + " array([1.41450159, 0.07926474, 1.41367222, 2.78688475])],\n", + " True)" + ] + }, + "execution_count": 72, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "ddp.solve(init_xs=xs0, init_us=us0, maxiter=150)" + ] + }, + { + "cell_type": "code", + "execution_count": 73, + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<matplotlib.figure.Figure at 0x7ff760362290>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<matplotlib.figure.Figure at 0x7ff75fd87550>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<matplotlib.figure.Figure at 0x7ff760552290>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "distanceRotorCOG = 0.1525\n", + "cf = 6.6e-5\n", + "cm = 1e-6\n", + "pltUAM = PlotUAM('+', ddp.xs, ddp.us, np.size(ddp.us,0), dt, distanceRotorCOG, cf, cm)\n", + "\n", + "pltUAM.plotMotorForces();\n", + "pltUAM.plotFlyingPlatformActuation();\n", + "pltUAM.plotFlyingPlatformState();" + ] + }, + { + "cell_type": "code", + "execution_count": 74, + "metadata": {}, + "outputs": [], + "source": [ + "displayTrajectory(robot, ddp.xs, dt)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.12" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/examples/notebooks/quadcopter_mission.ipynb b/examples/notebooks/quadcopter_mission.ipynb deleted file mode 100644 index aca5726c484f6b7771d0542df09e37b8238d6f5d..0000000000000000000000000000000000000000 --- a/examples/notebooks/quadcopter_mission.ipynb +++ /dev/null @@ -1,527 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "from crocoddyl import *\n", - "import pinocchio as pin\n", - "import numpy as np\n", - "from crocoddyl.diagnostic import displayTrajectory" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "# LOAD ROBOT\n", - "robot = loadHector()\n", - "robot.initViewer(loadModel=True)\n", - "robot.display(robot.q0)\n", - "\n", - "robot.framesForwardKinematics(robot.q0)\n", - "\n", - "rmodel = robot.model" - ] - }, - { - "cell_type": "code", - "execution_count": 30, - "metadata": {}, - "outputs": [], - "source": [ - "def uavPlacementModel(targetPos, targetQuat, integrationStep, frameName):\n", - " # ACTUATION MODEL\n", - " distanceRotorCOG = 0.1525\n", - " cf = 6.6e-5\n", - " cm = 1e-6\n", - " actModel = ActuationModelUAM(robot.model, distanceRotorCOG, cf, cm)\n", - "\n", - " # COST MODEL\n", - " # Create a cost model per the running and terminal action model.\n", - " runningCostModel = CostModelSum(rmodel, actModel.nu)\n", - " terminalCostModel = CostModelSum(rmodel, actModel.nu)\n", - "\n", - " state = StatePinocchio(rmodel)\n", - " SE3ref = pin.SE3()\n", - " SE3ref.translation = targetPos.reshape(3,1)\n", - " SE3ref.rotation = targetQuat.matrix()\n", - "\n", - " wBasePos = [10]\n", - " wBaseOri = [1]\n", - " wBaseVel = [100]\n", - " wBaseRate = [10]\n", - " \n", - " stateWeights = np.array(wBasePos * 3 + wBaseOri * 3 + wBaseVel * robot.model.nv)\n", - " controlWeights = np.array([10]*4)\n", - " \n", - " goalTrackingCost = CostModelFramePlacement(rmodel,\n", - " frame=rmodel.getFrameId(frameName),\n", - " ref=SE3ref,\n", - " nu =actModel.nu)\n", - " xRegCost = CostModelState(rmodel, \n", - " state, \n", - " ref=state.zero(), \n", - " nu=actModel.nu,\n", - " activation=ActivationModelWeightedQuad(stateWeights))\n", - " uRegCost = CostModelControl(rmodel, \n", - " nu=robot.\n", - " model.nv-2,\n", - " activation = ActivationModelWeightedQuad(controlWeights))\n", - " uLimCost = CostModelControl(rmodel, \n", - " nu=robot.\n", - " model.nv-2,\n", - " activation = ActivationModelInequality(np.array([0.1, 0.1, 0.1, 0.1, -1, -1, -1, -1, -1, -1]), \n", - " np.array([5, 5, 5, 5, 1, 1, 1, 1, 1, 1])))\n", - "\n", - " # Then let's add the running and terminal cost functions\n", - " runningCostModel.addCost(name=\"pos\", weight=0.1, cost=goalTrackingCost)\n", - " runningCostModel.addCost(name=\"regx\", weight=1e-4, cost=xRegCost)\n", - " runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n", - " # runningCostModel.addCost(name=\"limu\", weight=1e-3, cost=uLimCost)\n", - " terminalCostModel.addCost(name=\"pos\", weight=50, cost=goalTrackingCost)\n", - "\n", - " # DIFFERENTIAL ACTION MODEL\n", - " runningDmodel = DifferentialActionModelActuated(rmodel, actModel, runningCostModel)\n", - " terminalDmodel = DifferentialActionModelActuated(rmodel, actModel, terminalCostModel)\n", - " runningModel = IntegratedActionModelEuler(runningDmodel)\n", - " runningModel.timeStep = integrationStep \n", - " terminalModel = IntegratedActionModelEuler(terminalDmodel)\n", - " terminalModel.timeStep = integrationStep \n", - " \n", - " return runningModel,terminalModel " - ] - }, - { - "cell_type": "code", - "execution_count": 31, - "metadata": { - "scrolled": true - }, - "outputs": [], - "source": [ - "# DEFINING THE SHOOTING PROBLEM & SOLVING\n", - "\n", - "# Defining the time duration for running action models and the terminal one\n", - "dt = 5e-2\n", - "T = 25\n", - "\n", - "\n", - "# DEFINE POSITION WAYPOINTS\n", - "target_pos = [np.array([0,0,1])]\n", - "target_pos += [np.array([0,1,1])]\n", - "quat = pin.Quaternion(1, 0, 0, 0)\n", - "quat.normalize()\n", - "target_quat = [quat]*2\n", - "\n", - "# Plot goal frame\n", - "for i in range(0,len(target_pos)):\n", - " robot.viewer.gui.addXYZaxis('world/wp%i' % i, [1., 0., 0., 1.], .03, 0.5)\n", - " robot.viewer.gui.applyConfiguration('world/wp%i' % i, \n", - " target_pos[i].tolist() + [target_quat[i][0], target_quat[i][1], target_quat[i][2], target_quat[i][3]])\n", - " \n", - "robot.viewer.gui.refresh()" - ] - }, - { - "cell_type": "code", - "execution_count": 32, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 0 3.68073e+00 1.25267e+00 1.56079e+02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 1 1.00058e+00 1.66607e-01 5.80878e+00 1.00000e-09 1.00000e-09 1.0000 1\n", - " 2 8.01123e-01 6.25271e-03 3.87854e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 3 7.95405e-01 6.31666e-05 9.12472e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 4 7.94369e-01 1.35846e-05 1.46894e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 5 7.94137e-01 1.45173e-06 3.08133e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 6 7.94073e-01 3.43830e-07 8.33311e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 7 7.94053e-01 8.34184e-08 2.54417e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 8 7.94046e-01 2.26953e-08 8.44421e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 9 7.94044e-01 6.57880e-09 2.98715e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 10 7.94043e-01 2.02090e-09 1.11154e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 11 7.94042e-01 6.54583e-10 4.30544e-07 1.00000e-09 1.00000e-09 1.0000 1\n" - ] - }, - { - "data": { - "text/plain": [ - "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0.]),\n", - " array([ 0.00000000e+00, -1.01480409e-03, 1.19047887e-01, 8.52402554e-03,\n", - " 0.00000000e+00, 0.00000000e+00, 9.99963670e-01, 0.00000000e+00,\n", - " 0.00000000e+00, 2.38107307e+00, 3.40965151e-01, 0.00000000e+00,\n", - " 0.00000000e+00]),\n", - " array([ 0.00000000e+00, -2.05452635e-03, 2.40532823e-01, 1.32991567e-02,\n", - " 0.00000000e+00, 0.00000000e+00, 9.99911562e-01, 0.00000000e+00,\n", - " 3.22313817e-02, 2.42958316e+00, 1.91016801e-01, 0.00000000e+00,\n", - " 0.00000000e+00]),\n", - " array([ 6.20694709e-19, -3.17269406e-03, 3.47519141e-01, 1.69621642e-02,\n", - " 5.85347588e-18, 1.28108662e-17, 9.99856132e-01, 0.00000000e+00,\n", - " 4.23906229e-02, 2.13942809e+00, 1.46537158e-01, 2.40933816e-16,\n", - " 5.09276617e-16]),\n", - " array([ 7.39828124e-19, -4.47708649e-03, 4.39445718e-01, 1.97573253e-02,\n", - " 5.97249921e-18, 1.27958640e-17, 9.99804805e-01, -1.91653387e-17,\n", - " 4.14284192e-02, 1.83825224e+00, 1.11825327e-01, 3.32975393e-18,\n", - " 0.00000000e+00]),\n", - " array([ 2.82903512e-20, -6.11495486e-03, 5.18076058e-01, 2.16208694e-02,\n", - " -6.21631369e-18, 2.52777666e-17, 9.99766242e-01, -1.38615156e-17,\n", - " 3.23284242e-02, 1.57261657e+00, 7.45577350e-02, -4.78537878e-16,\n", - " 5.09276617e-16]),\n", - " array([ 1.22173209e-19, -8.22995470e-03, 5.85251623e-01, 2.24867613e-02,\n", - " -6.34412454e-18, 3.80147943e-17, 9.99747141e-01, 1.79565984e-17,\n", - " 1.69858459e-02, 1.34406989e+00, 3.46441018e-02, 5.02392430e-18,\n", - " 5.09276617e-16]),\n", - " array([ 7.46264988e-19, -1.09375178e-02, 6.42578223e-01, 2.23178458e-02,\n", - " 6.69723767e-18, 1.01791822e-19, 9.99750926e-01, 1.09908975e-17,\n", - " -2.73988432e-03, 1.14780682e+00, -6.75831681e-03, 4.87678772e-16,\n", - " -1.52782985e-15]),\n", - " array([ 1.50332253e-18, -1.43114155e-02, 6.91417153e-01, 2.10985944e-02,\n", - " 1.86134041e-17, 1.31110558e-17, 9.99777400e-01, -1.02217246e-17,\n", - " -2.50161000e-02, 9.78787186e-01, -4.87815526e-02, 4.88139478e-16,\n", - " 5.09276617e-16]),\n", - " array([ 1.38823642e-18, -1.83759631e-02, 7.32916721e-01, 1.88250001e-02,\n", - " -6.18127693e-18, 5.08349481e-17, 9.99822794e-01, -1.67636478e-17,\n", - " -4.80965517e-02, 8.32575408e-01, -9.09619180e-02, -9.58571878e-16,\n", - " 1.52782985e-15]),\n", - " array([ 2.11979091e-18, -2.31014793e-02, 7.68041906e-01, 1.54966236e-02,\n", - " -7.09542862e-18, 8.90025088e-17, 9.99879920e-01, 1.24648098e-17,\n", - " -7.03472371e-02, 7.05334513e-01, -1.33154727e-01, -1.03737825e-18,\n", - " 1.52782985e-15]),\n", - " array([ 3.37890076e-18, -2.84018226e-02, 7.97596119e-01, 1.11111793e-02,\n", - " 1.57599703e-17, 1.27531017e-16, 9.99938269e-01, -1.18534821e-18,\n", - " -9.02435306e-02, 5.93697289e-01, -1.75433442e-01, 9.53620889e-16,\n", - " 1.52782985e-15]),\n", - " array([ 4.48647299e-18, -3.41333794e-02, 8.22235124e-01, 5.66132259e-03,\n", - " 1.43714229e-17, 1.40339950e-16, 9.99983975e-01, -2.23178132e-17,\n", - " -1.06350643e-01, 4.94635820e-01, -2.18002203e-01, -2.20734625e-17,\n", - " 5.09276617e-16]),\n", - " array([ 6.06502138e-18, -4.00952370e-02, 8.42473940e-01, -8.66786731e-04,\n", - " 1.28513812e-17, 1.27695332e-16, 9.99999624e-01, -1.11612658e-17,\n", - " -1.17295896e-01, 4.05346237e-01, -2.61125587e-01, -2.70271119e-17,\n", - " -5.09276617e-16]),\n", - " array([ 7.62758000e-18, -4.60305688e-02, 8.58687428e-01, -8.49358986e-03,\n", - " -1.27764835e-17, 8.96156123e-17, 9.99963929e-01, 5.08908583e-18,\n", - " -1.21737892e-01, 3.23147560e-01, -3.05076206e-01, -9.84828837e-16,\n", - " -1.52782985e-15]),\n", - " array([ 9.03625127e-18, -5.16295149e-02, 8.71105059e-01, -1.72453830e-02,\n", - " -1.38921858e-17, 5.13065366e-17, 9.99851287e-01, 1.85144949e-17,\n", - " -1.18335213e-01, 2.45391464e-01, -3.50101838e-01, -2.96894800e-19,\n", - " -1.52782985e-15]),\n", - " array([ 9.99403875e-18, -5.65340697e-02, 8.79800445e-01, -2.71532989e-02,\n", - " -1.40303957e-17, 3.84263672e-17, 9.99631281e-01, 1.47997233e-17,\n", - " -1.05715608e-01, 1.69384992e-01, -3.96415952e-01, 2.35691263e-17,\n", - " -5.09276617e-16]),\n", - " array([ 1.02946252e-17, -6.03456269e-02, 8.84676850e-01, -3.82527161e-02,\n", - " -2.63727585e-18, -2.61904871e-19, 9.99268097e-01, 4.55686956e-18,\n", - " -8.24453890e-02, 9.23379978e-02, -4.44216581e-01, 5.14444491e-16,\n", - " -1.52782985e-15]),\n", - " array([ 1.05480478e-17, -6.26359361e-02, 8.85449365e-01, -5.05838756e-02,\n", - " -1.35881541e-17, -1.26160152e-17, 9.98719816e-01, 5.88475490e-18,\n", - " -4.69978433e-02, 1.13242950e-02, -4.93736837e-01, -4.19009063e-16,\n", - " -5.09276617e-16]),\n", - " array([ 1.03098078e-17, -6.29621406e-02, 8.81625850e-01, -6.41947662e-02,\n", - " -1.09213721e-17, -1.78543908e-19, 9.97937389e-01, -6.62020700e-18,\n", - " 2.28185125e-03, -7.67165557e-02, -5.45338670e-01, 7.40777180e-17,\n", - " 5.09276617e-16]),\n", - " array([ 9.60164119e-18, -6.08785820e-02, 8.72542778e-01, -7.91461825e-02,\n", - " -8.56126497e-18, 1.22639541e-17, 9.96863021e-01, -1.69809643e-17,\n", - " 6.72188490e-02, -1.73843590e-01, -5.99604301e-01, 6.16860243e-17,\n", - " 5.09276617e-16]),\n", - " array([ 8.49988271e-18, -5.58873700e-02, 8.57736870e-01, -9.55036145e-02,\n", - " 3.43695196e-18, -1.61817631e-18, 9.95429083e-01, -2.21531807e-17,\n", - " 1.49829560e-01, -2.74245740e-01, -6.56813907e-01, 5.29928889e-16,\n", - " -5.09276617e-16]),\n", - " array([ 7.26181196e-18, -4.68862013e-02, 8.39432447e-01, -1.13173011e-01,\n", - " 1.82394028e-17, 9.81537217e-18, 9.93575296e-01, -1.54972453e-17,\n", - " 2.52096781e-01, -3.20770779e-01, -7.10664350e-01, 5.44853627e-16,\n", - " 5.09276617e-16]),\n", - " array([ 7.59005172e-18, -2.77881062e-02, 8.38782240e-01, -1.30260589e-01,\n", - " 8.70322370e-18, 2.40081804e-17, 9.91479793e-01, 1.85283878e-17,\n", - " 3.73804235e-01, 7.96795268e-02, -6.88632007e-01, -4.35030016e-16,\n", - " 5.09276617e-16]),\n", - " array([ 1.13929007e-17, 1.82559252e-02, 1.00131745e+00, 2.00556445e-03,\n", - " -2.41405129e-17, -1.64687187e-16, 9.99997989e-01, 4.13130436e-17,\n", - " 4.97757618e-01, 3.35179262e+00, 5.30549475e+00, -4.50677754e-16,\n", - " -7.63914925e-15]),\n", - " array([ 2.84248969e-17, 8.74538207e-02, 1.00589868e+00, 9.53309136e-03,\n", - " 1.44924136e-17, -1.51689014e-16, 9.99954559e-01, -9.66380548e-17,\n", - " 1.38493607e+00, 7.56502988e-02, 3.01106799e-01, 1.59591733e-15,\n", - " 5.09276617e-16]),\n", - " array([ 4.58256445e-17, 1.56348753e-01, 1.00474137e+00, 1.85587387e-02,\n", - " 4.88393744e-18, -1.39159872e-16, 9.99827772e-01, -5.17738563e-17,\n", - " 1.37672348e+00, -6.18421268e-02, 3.61062739e-01, -3.24711174e-16,\n", - " 5.09276617e-16]),\n", - " array([ 6.34581031e-17, 2.24468053e-01, 1.00098617e+00, 2.82206369e-02,\n", - " -1.66530879e-17, -1.26841464e-16, 9.99601719e-01, -1.03973650e-17,\n", - " 1.35740404e+00, -1.38738972e-01, 3.86583193e-01, -7.98374402e-16,\n", - " 5.09276617e-16]),\n", - " array([ 8.36041668e-17, 2.91297280e-01, 9.95950811e-01, 3.77879072e-02,\n", - " -3.65201963e-17, -1.65413253e-16, 9.99285782e-01, 5.81042274e-18,\n", - " 1.32704892e+00, -1.88669588e-01, 3.82900880e-01, -7.89590099e-16,\n", - " -1.52782985e-15]),\n", - " array([ 9.76026301e-17, 3.56303351e-01, 9.90557863e-01, 4.67000689e-02,\n", - " 1.33747566e-17, -1.50397550e-16, 9.98908957e-01, -1.32682273e-16,\n", - " 1.28639337e+00, -2.17224529e-01, 3.56806166e-01, 2.07551380e-15,\n", - " 5.09276617e-16]),\n", - " array([ 1.12976580e-16, 4.18962776e-01, 9.85601101e-01, 5.45395391e-02,\n", - " -3.26349926e-17, -1.39848005e-16, 9.98511612e-01, -5.73866950e-17,\n", - " 1.23675523e+00, -2.25340136e-01, 3.13982146e-01, -1.77131957e-15,\n", - " 5.09276617e-16]),\n", - " array([ 1.27292195e-16, 4.78807971e-01, 9.81646719e-01, 6.10308109e-02,\n", - " -2.87731866e-17, -1.52123093e-16, 9.98135883e-01, -7.03365876e-17,\n", - " 1.17979394e+00, -2.16657184e-01, 2.60085930e-01, 1.63285551e-16,\n", - " -5.09276617e-16]),\n", - " array([ 1.39819406e-16, 5.35460287e-01, 9.79009684e-01, 6.60305765e-02,\n", - " -4.88792345e-17, -1.65915476e-16, 9.97817600e-01, -1.17675894e-16,\n", - " 1.11721685e+00, -1.95991835e-01, 2.00395658e-01, -8.06359629e-16,\n", - " -5.09276617e-16]),\n", - " array([ 1.46071366e-16, 5.88646403e-01, 9.77776523e-01, 6.95091215e-02,\n", - " -2.41265357e-17, -1.25788568e-16, 9.97581316e-01, -1.91125052e-16,\n", - " 1.05061842e+00, -1.68282366e-01, 1.39462498e-01, 1.11655732e-15,\n", - " 1.52782985e-15]),\n", - " array([ 1.52028909e-16, 6.38198872e-01, 9.77857485e-01, 7.15256925e-02,\n", - " 2.81773437e-18, -1.11081632e-16, 9.97438758e-01, -1.16505455e-16,\n", - " 9.81421447e-01, -1.37821536e-01, 8.08641605e-02, 1.12606431e-15,\n", - " 5.09276617e-16]),\n", - " array([ 1.58192185e-16, 6.84045501e-01, 9.79048734e-01, 7.22025672e-02,\n", - " -4.21379991e-17, -1.01537252e-16, 9.97389989e-01, -7.32035604e-17,\n", - " 9.10877216e-01, -1.07869502e-01, 2.71451732e-02, -1.76330401e-15,\n", - " 5.09276617e-16]),\n", - " array([ 1.63850939e-16, 7.26193067e-01, 9.81090695e-01, 7.17017312e-02,\n", - " -5.92508428e-17, -1.41096611e-16, 9.97426118e-01, -9.35570030e-17,\n", - " 8.40084960e-01, -8.05735538e-02, -2.00855017e-02, -7.98951926e-16,\n", - " -1.52782985e-15]),\n", - " array([ 1.64720669e-16, 7.64709813e-01, 9.83714776e-01, 7.02063533e-02,\n", - " -2.99518707e-17, -1.51859047e-16, 9.97532490e-01, -2.09001886e-16,\n", - " 7.70007525e-01, -5.70880962e-02, -5.99662584e-02, 1.12988781e-15,\n", - " -5.09276617e-16]),\n", - " array([ 1.61798362e-16, 7.99709392e-01, 9.86676044e-01, 6.79075619e-02,\n", - " -2.81059040e-17, -1.13532182e-16, 9.97691617e-01, -2.44235451e-16,\n", - " 7.01476203e-01, -3.77873875e-02, -9.21717177e-02, 1.67515152e-16,\n", - " 1.52782985e-15]),\n", - " array([ 1.58843857e-16, 8.31337345e-01, 9.89772885e-01, 6.49959262e-02,\n", - " -2.28884083e-17, -1.26042500e-16, 9.97885529e-01, -2.10277174e-16,\n", - " 6.35186810e-01, -2.24938043e-02, -1.16723471e-01, 1.61231917e-16,\n", - " -5.09276617e-16]),\n", - " array([ 1.53589551e-16, 8.59760117e-01, 9.92856254e-01, 6.16565873e-02,\n", - " -1.92056222e-17, -1.13147115e-16, 9.98097423e-01, -2.40639583e-16,\n", - " 5.71691905e-01, -1.06791433e-02, -1.33842256e-01, 1.63884217e-16,\n", - " 5.09276617e-16]),\n", - " array([ 1.46445049e-16, 8.85156168e-01, 9.95831519e-01, 5.80669475e-02,\n", - " -6.52351922e-17, -7.78155545e-17, 9.98312691e-01, -2.37955763e-16,\n", - " 5.11393336e-01, -1.62231847e-03, -1.43843629e-01, -1.76662760e-15,\n", - " 1.52782985e-15]),\n", - " array([ 1.37148563e-16, 9.07708513e-01, 9.98655546e-01, 5.43960109e-02,\n", - " -3.63871145e-17, -8.91470037e-17, 9.98519441e-01, -2.58488048e-16,\n", - " 4.54537444e-01, 5.47748665e-03, -1.47070247e-01, 1.11477255e-15,\n", - " -5.09276617e-16]),\n", - " array([ 1.25271107e-16, 9.27598152e-01, 1.00133094e+00, 5.08047264e-02,\n", - " -5.69627494e-17, -7.76648882e-17, 9.98708606e-01, -3.01253424e-16,\n", - " 4.01213685e-01, 1.14214889e-02, -1.43850600e-01, -8.09356116e-16,\n", - " 5.09276617e-16]),\n", - " array([ 1.10472452e-16, 9.44998037e-01, 1.00389775e+00, 4.74469232e-02,\n", - " -2.95130719e-17, -6.37245173e-17, 9.98873761e-01, -3.42512303e-16,\n", - " 3.51356461e-01, 1.69383621e-02, -1.34474557e-01, 1.11484571e-15,\n", - " 5.09276617e-16]),\n", - " array([ 9.40597891e-17, 9.60067271e-01, 1.00642311e+00, 4.44704547e-02,\n", - " -5.02961714e-17, -5.20621513e-17, 9.99010700e-01, -3.60463236e-16,\n", - " 3.04749562e-01, 2.26206476e-02, -1.19184722e-01, -8.15680480e-16,\n", - " 5.09276617e-16]),\n", - " array([ 7.54786195e-17, 9.72947595e-01, 1.00896289e+00, 4.20190623e-02,\n", - " -2.19024949e-17, -6.36716795e-17, 9.99116809e-01, -3.98801077e-16,\n", - " 2.61032403e-01, 2.83462133e-02, -9.81475344e-02, 1.10908182e-15,\n", - " -5.09276617e-16]),\n", - " array([ 5.55995550e-17, 9.83771923e-01, 1.01136885e+00, 4.02354425e-02,\n", - " -4.16397462e-17, -7.72886957e-17, 9.99190227e-01, -4.25862655e-16,\n", - " 2.19709003e-01, 3.01645042e-02, -7.14052182e-02, -8.16158507e-16,\n", - " -5.09276617e-16]),\n", - " array([ 3.41284949e-17, 9.92745206e-01, 1.01216431e+00, 3.92436001e-02,\n", - " -3.52746748e-17, -1.40787930e-16, 9.99229673e-01, -4.67991190e-16,\n", - " 1.80162301e-01, 1.60654784e-03, -3.97050602e-02, 1.49199294e-16,\n", - " -2.54638308e-15]),\n", - " array([ 9.70687943e-18, 1.00031923e+00, 9.99794061e-01, 1.11666474e-06,\n", - " -7.30987889e-18, -1.06046509e-18, 1.00000000e+00, -5.20099036e-16,\n", - " 1.41690796e-01, -2.53224277e-01, -1.57010253e+00, 1.11744564e-15,\n", - " 5.60204278e-15])],\n", - " [array([21.07778292, 21.33535135, 21.33535135, 21.07778292]),\n", - " array([4.03669933, 3.92342687, 3.92342687, 4.03669933]),\n", - " array([1.49733952, 1.46373916, 1.46373916, 1.49733952]),\n", - " array([1.41147897, 1.38525731, 1.38525731, 1.41147897]),\n", - " array([1.67358194, 1.64542963, 1.64542963, 1.67358194]),\n", - " array([1.94710421, 1.91695306, 1.91695306, 1.94710421]),\n", - " array([2.18513161, 2.15385582, 2.15385582, 2.18513161]),\n", - " array([2.38640324, 2.35465848, 2.35465848, 2.38640324]),\n", - " array([2.55572588, 2.52386242, 2.52386242, 2.55572588]),\n", - " array([2.697653 , 2.66578014, 2.66578014, 2.697653 ]),\n", - " array([2.81558949, 2.78365173, 2.78365173, 2.81558949]),\n", - " array([2.91180343, 2.87964657, 2.87964657, 2.91180343]),\n", - " array([2.98755559, 2.95497976, 2.95497976, 2.98755559]),\n", - " array([3.04320993, 3.0100092 , 3.0100092 , 3.04320993]),\n", - " array([3.07831119, 3.04429839, 3.04429839, 3.07831119]),\n", - " array([3.09167098, 3.05668484, 3.05668484, 3.09167098]),\n", - " array([3.08153775, 3.04542869, 3.04542869, 3.08153775]),\n", - " array([3.04568268, 3.0082746 , 3.0082746 , 3.04568268]),\n", - " array([2.98168219, 2.94270166, 2.94270166, 2.98168219]),\n", - " array([2.89524114, 2.85424835, 2.85424835, 2.89524114]),\n", - " array([2.8422169, 2.7990002, 2.7990002, 2.8422169]),\n", - " array([3.19667838, 3.15599922, 3.15599922, 3.19667838]),\n", - " array([6.41240199, 6.42904544, 6.42904544, 6.41240199]),\n", - " array([25.30491009, 29.83293241, 29.83293241, 25.30491009]),\n", - " array([-17.70668175, -21.48704563, -21.48704563, -17.70668175]),\n", - " array([2.73763918, 2.78293049, 2.78293049, 2.73763918]),\n", - " array([3.22587294, 3.24515134, 3.24515134, 3.22587294]),\n", - " array([3.44298982, 3.44020816, 3.44020816, 3.44298982]),\n", - " array([3.59860182, 3.57888962, 3.57888962, 3.59860182]),\n", - " array([3.73226688, 3.69991719, 3.69991719, 3.73226688]),\n", - " array([3.82866001, 3.78794628, 3.78794628, 3.82866001]),\n", - " array([3.88382025, 3.83872964, 3.83872964, 3.88382025]),\n", - " array([3.90107427, 3.85504476, 3.85504476, 3.90107427]),\n", - " array([3.88852899, 3.84426322, 3.84426322, 3.88852899]),\n", - " array([3.85606928, 3.81548943, 3.81548943, 3.85606928]),\n", - " array([3.81312432, 3.7774458 , 3.7774458 , 3.81312432]),\n", - " array([3.76736928, 3.73724297, 3.73724297, 3.76736928]),\n", - " array([3.72428391, 3.69995559, 3.69995559, 3.72428391]),\n", - " array([3.6872762 , 3.66872956, 3.66872956, 3.6872762 ]),\n", - " array([3.65807802, 3.64514632, 3.64514632, 3.65807802]),\n", - " array([3.63721007, 3.62965493, 3.62965493, 3.63721007]),\n", - " array([3.62440358, 3.62196616, 3.62196616, 3.62440358]),\n", - " array([3.61890242, 3.62133458, 3.62133458, 3.61890242]),\n", - " array([3.61953263, 3.62661538, 3.62661538, 3.61953263]),\n", - " array([3.62477531, 3.6363254 , 3.6363254 , 3.62477531]),\n", - " array([3.628941 , 3.6448327, 3.6448327, 3.628941 ]),\n", - " array([3.60341858, 3.62361999, 3.62361999, 3.60341858]),\n", - " array([3.3819474 , 3.40589401, 3.40589401, 3.3819474 ]),\n", - " array([2.30465688, 1.14857958, 1.14857958, 2.30465688])],\n", - " True)" - ] - }, - "execution_count": 32, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "models = []\n", - "for i in range(0,len(target_pos)):\n", - " runningModel, terminalModel = uavPlacementModel(target_pos[i], target_quat[i], dt, 'base_link')\n", - " models += [runningModel]*(T-1) + [terminalModel]\n", - "\n", - "q0 = robot.q0\n", - "x0 = np.hstack([m2a(q0), np.zeros(robot.model.nv)])\n", - "\n", - "problem = ShootingProblem(x0, models[:-1], models[-1])\n", - "\n", - "# Creating the DDP solver for this OC problem, defining a logger\n", - "ddp = SolverFDDP(problem)\n", - "ddp.callback = [CallbackDDPVerbose()]\n", - "ddp.callback.append(CallbackDDPLogger())\n", - "\n", - "# Solving it with the DDP algorithm\n", - "ddp.solve(maxiter=150)" - ] - }, - { - "cell_type": "code", - "execution_count": 28, - "metadata": {}, - "outputs": [], - "source": [ - "displayTrajectory(robot, ddp.xs, dt)\n" - ] - }, - { - "cell_type": "code", - "execution_count": 33, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "<Figure size 1080x720 with 4 Axes>" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "distanceRotorCOG = 0.1525\n", - "cf = 6.6e-5\n", - "cm = 1e-6\n", - "pltUAM = PlotUAM(ddp.xs, ddp.us, np.size(ddp.us,0), dt, distanceRotorCOG, cf, cm)\n", - "\n", - "fig, axs = pltUAM.plotMotorForces()" - ] - }, - { - "cell_type": "code", - "execution_count": 13, - "metadata": {}, - "outputs": [ - { - "ename": "AttributeError", - "evalue": "'list' object has no attribute 'set_title'", - "output_type": "error", - "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mAttributeError\u001b[0m Traceback (most recent call last)", - "\u001b[0;32m<ipython-input-13-6afaa0e0f774>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m 3\u001b[0m \u001b[0mfig\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mplt\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfigure\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 4\u001b[0m \u001b[0maxs\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mplt\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mplot\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mt\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcontrol\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 5\u001b[0;31m \u001b[0maxs\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mset_title\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'Moments'\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m", - "\u001b[0;31mAttributeError\u001b[0m: 'list' object has no attribute 'set_title'" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "<Figure size 432x288 with 1 Axes>" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "t = np.arange(0, 2*T*dt-dt, dt)\n", - "control = np.vstack(ddp.us)\n", - "fig = plt.figure()\n", - "axs = plt.plot(t, control[:,1])\n", - "axs.set_title('Moments')" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 2", - "language": "python", - "name": "python2" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 2 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.15+" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -}