File: torso_sockets.py

package info (click to toggle)
morse-simulator 1.4-8
  • links: PTS, VCS
  • area: main
  • in suites: bookworm
  • size: 187,116 kB
  • sloc: ansic: 108,311; python: 25,694; cpp: 786; makefile: 126; xml: 34; sh: 7
file content (95 lines) | stat: -rwxr-xr-x 3,319 bytes parent folder | download | duplicates (4)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
#! /usr/bin/env python
"""
This script tests the PR2 torso armature joint
"""

from morse.testing.testing import MorseTestCase
import logging; logger = logging.getLogger("morsetesting.general")

# Include this import to be able to use your test file as a regular 
# builder script, ie, usable with: 'morse [run|exec] base_testing.py
try:
    from morse.builder import *
except ImportError:
    pass

import sys

from pymorse import Morse

def getjoint(simu, name):
    joints = simu.pr2.joint_state.get()
    return joints[name]

class PR2TorsoTest(MorseTestCase):

    def setUpEnv(self):
        from morse.builder.robots import BasePR2
        pr2 = BasePR2()
        pr2.add_interface('socket')

        env = Environment('empty', fastmode=True)
        env.set_camera_rotation([1.0470, 0, 0.7854])

    def test_torso_translate(self):
        

        joint = "torso_lift_joint"

        with Morse() as simu:
            
            self.assertAlmostEquals(getjoint(simu, joint), 0.0, 3)

            logger.info("Moving up torso to 0.2m...")
            action = simu.pr2.torso.translate(joint, 0.2, 0.1) # speed = 0.1 m/s

            simu.sleep(1)
            logger.info("Should be now at 0.1m...")
            self.assertAlmostEquals(getjoint(simu, joint), 0.1, 1)

            simu.sleep(1)
            logger.info("Should be now at 0.2m...")
            self.assertAlmostEquals(getjoint(simu, joint), 0.2, 1)

            # Check we do not move anymore
            logger.info("Should not move anymore...")
            simu.sleep(0.5)
            self.assertFalse(action.running())
            self.assertAlmostEquals(getjoint(simu, joint), 0.2, 1)

            # Test limits
            #TODO: currently no way to stop the action when blocking on a joint limit since we can not retreive them from Python (blender 2.64)
            #logger.info("Let's go as high as possible to check my limits...")
            #action = simu.pr2.torso.translate(joint, [0, 1, 0], 0.2) # speed = 0.2 m/s
            #simu.sleep(2)
            #self.assertFalse(action.running())
            #self.assertAlmostEquals(getjoint(simu, joint), 0.3, 1)

            # Go back to initial position
            logger.info("Let's go back down...")
            action = simu.pr2.torso.translate(joint, 0, 0.2) # speed = 0.2 m/s
            simu.sleep(1.6)
            self.assertFalse(action.running())
            self.assertAlmostEquals(getjoint(simu, joint), 0.0, 1)

            ## Testing set_translation
            logger.info("Moving up torso to 0.2m...")
            simu.pr2.torso.set_translation(joint, 0.2)
            logger.info("Should be now at 0.2m...")
            simu.sleep(.1)
            self.assertAlmostEquals(getjoint(simu, joint), 0.2, 3)

            # Test limits
            logger.info("Let's go as high as possible to check my limits...")
            simu.pr2.torso.set_translation(joint, 1)
            simu.sleep(.1)
            self.assertAlmostEquals(getjoint(simu, joint), 0.31, 3)
            simu.pr2.torso.set_translation(joint, -1)
            simu.sleep(.1)
            self.assertAlmostEquals(getjoint(simu, joint), 0.0, 3)


########################## Run these tests ##########################
if __name__ == "__main__":
    from morse.testing.testing import main
    main(PR2TorsoTest)