|
1 | | -import pinocchio as se3 |
2 | 1 | import pinocchio as pin |
3 | | -#from pinocchio import libpinocchio_pywrap as pin |
4 | 2 | import tsid |
5 | 3 | import numpy as np |
6 | 4 | from numpy import nan |
|
43 | 41 | filename = str(os.path.dirname(os.path.abspath(__file__))) |
44 | 42 | path = filename + '/../models' |
45 | 43 | urdf = path + '/quadruped/urdf/quadruped.urdf' |
46 | | -vector = se3.StdVec_StdString() |
| 44 | +vector = pin.StdVec_StdString() |
47 | 45 | vector.extend(item for item in path) |
48 | | -robot = tsid.RobotWrapper(urdf, vector, se3.JointModelFreeFlyer(), False) |
| 46 | +robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(), False) |
49 | 47 |
|
50 | 48 | # for gepetto viewer |
51 | | -robot_display = se3.RobotWrapper.BuildFromURDF(urdf, [path, ], se3.JointModelFreeFlyer()) |
| 49 | +robot_display = pin.RobotWrapper.BuildFromURDF(urdf, [path, ], pin.JointModelFreeFlyer()) |
52 | 50 | l = subprocess.getstatusoutput("ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l") |
53 | 51 | if int(l[1]) == 0: |
54 | 52 | os.system('gepetto-gui &') |
|
60 | 58 | #model = robot.model() |
61 | 59 | #pin.loadReferenceConfigurations(model, srdf, False) |
62 | 60 | #q = model.referenceConfigurations["half_sitting"] |
63 | | -#q = se3.getNeutralConfigurationFromSrdf(robot.model(), srdf, False) |
| 61 | +#q = pin.getNeutralConfigurationFromSrdf(robot.model(), srdf, False) |
64 | 62 | #q = robot_display.model.neutralConfiguration #np.zeros(robot.nq) |
65 | 63 | q = np.zeros(robot.nq) |
66 | 64 | q[6] = 1.0 |
|
113 | 111 | q_ref = q[7:] |
114 | 112 | trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q_ref) |
115 | 113 |
|
116 | | -print("Create QP solver with ", invdyn.nVar, " variables, ", invdyn.nEq, |
| 114 | +print("Create QP solver with ", invdyn.nVar, " variables, ", invdyn.nEq, |
117 | 115 | " equality and ", invdyn.nIn, " inequality constraints") |
118 | 116 | solver = tsid.SolverHQuadProgFast("qp solver") |
119 | 117 | solver.resize(invdyn.nVar, invdyn.nEq, invdyn.nIn) |
|
176 | 174 |
|
177 | 175 | v_mean = v + 0.5*dt*dv |
178 | 176 | v += dt*dv |
179 | | - q = se3.integrate(robot.model(), q, dt*v_mean) |
| 177 | + q = pin.integrate(robot.model(), q, dt*v_mean) |
180 | 178 | t += dt |
181 | 179 |
|
182 | 180 | if i%DISPLAY_N == 0: robot_display.display(q) |
|
0 commit comments