Skip to content

Commit edb4399

Browse files
authored
Merge pull request #171 from nim65s/devel
Fix unittest on 18.04
2 parents ce649ac + 4333bb5 commit edb4399

File tree

3 files changed

+7
-12
lines changed

3 files changed

+7
-12
lines changed

demo/demo_quadruped.py

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,4 @@
1-
import pinocchio as se3
21
import pinocchio as pin
3-
#from pinocchio import libpinocchio_pywrap as pin
42
import tsid
53
import numpy as np
64
from numpy import nan
@@ -43,12 +41,12 @@
4341
filename = str(os.path.dirname(os.path.abspath(__file__)))
4442
path = filename + '/../models'
4543
urdf = path + '/quadruped/urdf/quadruped.urdf'
46-
vector = se3.StdVec_StdString()
44+
vector = pin.StdVec_StdString()
4745
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)
4947

5048
# for gepetto viewer
51-
robot_display = se3.RobotWrapper.BuildFromURDF(urdf, [path, ], se3.JointModelFreeFlyer())
49+
robot_display = pin.RobotWrapper.BuildFromURDF(urdf, [path, ], pin.JointModelFreeFlyer())
5250
l = subprocess.getstatusoutput("ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")
5351
if int(l[1]) == 0:
5452
os.system('gepetto-gui &')
@@ -60,7 +58,7 @@
6058
#model = robot.model()
6159
#pin.loadReferenceConfigurations(model, srdf, False)
6260
#q = model.referenceConfigurations["half_sitting"]
63-
#q = se3.getNeutralConfigurationFromSrdf(robot.model(), srdf, False)
61+
#q = pin.getNeutralConfigurationFromSrdf(robot.model(), srdf, False)
6462
#q = robot_display.model.neutralConfiguration #np.zeros(robot.nq)
6563
q = np.zeros(robot.nq)
6664
q[6] = 1.0
@@ -113,7 +111,7 @@
113111
q_ref = q[7:]
114112
trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q_ref)
115113

116-
print("Create QP solver with ", invdyn.nVar, " variables, ", invdyn.nEq,
114+
print("Create QP solver with ", invdyn.nVar, " variables, ", invdyn.nEq,
117115
" equality and ", invdyn.nIn, " inequality constraints")
118116
solver = tsid.SolverHQuadProgFast("qp solver")
119117
solver.resize(invdyn.nVar, invdyn.nEq, invdyn.nIn)
@@ -176,7 +174,7 @@
176174

177175
v_mean = v + 0.5*dt*dv
178176
v += dt*dv
179-
q = se3.integrate(robot.model(), q, dt*v_mean)
177+
q = pin.integrate(robot.model(), q, dt*v_mean)
180178
t += dt
181179

182180
if i%DISPLAY_N == 0: robot_display.display(q)
File renamed without changes.

tests/python/test_Tasks.py

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -262,10 +262,7 @@
262262
print("")
263263

264264
# Get robot model generator module
265-
import sys
266-
filepath = os.path.normpath(os.path.join(os.path.dirname(os.path.abspath(__file__)), '../../'))
267-
sys.path.append(str(filepath))
268-
from models.arm.generator import create_7dof_arm
265+
from generator import create_7dof_arm
269266

270267
# Get robot model
271268
model, geom_model = create_7dof_arm() # A robot containing sperical joints where nq != nv

0 commit comments

Comments
 (0)