unittest_utils.py 2.44 KB
Newer Older
Carlos Mastalli's avatar
Carlos Mastalli committed
1
import numpy as np
2
3
4
5
6
import pinocchio
from pinocchio.robot_wrapper import RobotWrapper


def readParamsFromSrdf(robot, SRDF_PATH, verbose):
7
8
9
10
11
12
    rmodel = robot.model

    pinocchio.loadRotorParameters(rmodel, SRDF_PATH, verbose)
    rmodel.armature = \
        np.multiply(rmodel.rotorInertia.flat,
                    np.square(rmodel.rotorGearRatio.flat))
13
    try:
14
15
16
        pinocchio.loadReferenceConfigurations(rmodel, SRDF_PATH, verbose)
        robot.q0.flat[:] = \
            rmodel.referenceConfigurations["half_sitting"].copy()
17
    except:
18
19
20
21
22
23
24
25
26
27
        print "loadReferenceConfigurations did not work. Please check your \
            Pinocchio Version"
        try:
            pinocchio.getNeutralConfiguration(rmodel, SRDF_PATH, verbose)
            robot.q0.flat[:] = rmodel.neutralConfiguration.copy()
        except:
            robot.q0.flat[:] = pinocchio.neutral(rmodel)
    return


28
29
def loadTalosArm(modelPath='/opt/openrobots/share/example-robot-data'):
    URDF_FILENAME = "talos_left_arm.urdf"
30
    URDF_SUBPATH = "/talos/robots/" + URDF_FILENAME
31
    SRDF_FILENAME = "talos.srdf"
32
    SRDF_SUBPATH = "/talos/robots/" + SRDF_FILENAME
33
34
35
36
37
38
39
    # Load URDF file
    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath])

    # Load SRDF file
    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
    return robot

40

41
42
43
def loadTalos(modelPath='/opt/openrobots/share/example-robot-data'):
    URDF_FILENAME = "talos_reduced.urdf"
    SRDF_FILENAME = "talos.srdf"
44
45
    SRDF_SUBPATH = "/talos/robots/" + SRDF_FILENAME
    URDF_SUBPATH = "/talos/robots/" + URDF_FILENAME
46
47
    # Load URDF file
    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath],
48
                                       pinocchio.JointModelFreeFlyer())
49
50
    # Load SRDF file
    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
51
    assert((robot.model.armature[:6] == 0.).all())
52
53
54
55
56
    return robot


def loadHyQ(modelPath='/opt/openrobots/share/example-robot-data'):
    URDF_FILENAME = "hyq_no_sensors.urdf"
57
    URDF_SUBPATH = "/hyq/robots/" + URDF_FILENAME
58
59
60
    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath],
                                       pinocchio.JointModelFreeFlyer())
    # TODO define default position inside srdf
61
62
    robot.q0.flat[7:] = [-0.2, 0.75, -1.5, -0.2, -
                         0.75, 1.5, -0.2, 0.75, -1.5, -0.2, -0.75, 1.5]
63
64
65
    robot.q0[2] = 0.57750958
    robot.model.referenceConfigurations["half_sitting"] = robot.q0
    return robot