File: teleport_testing.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 (103 lines) | stat: -rwxr-xr-x 3,893 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
96
97
98
99
100
101
102
103
#! /usr/bin/env python
"""
This script tests the 'data stream' oriented feature of the socket interface.
"""

from morse.testing.testing import MorseTestCase

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

import os
import sys
import math
import random
from pymorse import Morse

def send_pose(s, x, y, z, yaw, pitch, roll):
    s.publish({'x' : x, 'y' : y, 'z' : z, 'yaw' : yaw, 'pitch' : pitch, 'roll' : roll})


class TeleportTest(MorseTestCase):

    def setUpEnv(self):
        
        robot = RMax('robot')
        robot.translate(10.0, 8.0, 20.0)
        
        pose = Pose()
        pose.add_stream('socket')
        robot.append(pose)

        teleport = Teleport('teleport')
        teleport.add_stream('socket')
        robot.append(teleport)


        env = Environment('empty', fastmode = True)
        env.add_service('socket')

    def _test_one_pose(self, morse, x, y, z, yaw, pitch, roll):
        send_pose(self.teleport_stream, x, y, z, yaw, pitch, roll)
        morse.sleep(0.2)

        pose = self.pose_stream.get()
        self.assertAlmostEqual(pose['yaw'], yaw, delta=self.precision)
        self.assertAlmostEqual(pose['pitch'], pitch, delta=self.precision)
        self.assertAlmostEqual(pose['roll'], roll, delta=self.precision)
        self.assertAlmostEqual(pose['x'], x, delta=self.precision)
        self.assertAlmostEqual(pose['y'], y, delta=self.precision)
        self.assertAlmostEqual(pose['z'], z, delta=self.precision)

    def test_teleport(self):
        """ Test if we can connect to the pose data stream, and read from it.
        """

        with Morse() as morse:
            self.pose_stream = morse.robot.pose
            self.teleport_stream = morse.robot.teleport

            self.precision = 0.15

            pose = self.pose_stream.get()
            self.assertAlmostEqual(pose['yaw'], 0.0, delta=self.precision)
            self.assertAlmostEqual(pose['pitch'], 0.0, delta=self.precision)
            self.assertAlmostEqual(pose['roll'], 0.0, delta=self.precision)
            self.assertAlmostEqual(pose['x'], 10.0, delta=self.precision)
            self.assertAlmostEqual(pose['y'], 8.0, delta=self.precision)
            self.assertAlmostEqual(pose['z'], 20.0, delta=self.precision)

            # Test only one rotation each time, otherwise, it a bit more
            # complex to check that it does the good transformation
            # (without a matrix transformation library)
            for i in range(0, 5):
                self._test_one_pose(morse,
                                    random.uniform(-30.0, 30.0),
                                    random.uniform(-30.0, 30.0),
                                    random.uniform(10.0, 50.0),
                                    random.uniform(-math.pi, math.pi),
                                    0, 0)
                self._test_one_pose(morse,
                                    random.uniform(-30.0, 30.0),
                                    random.uniform(-30.0, 30.0),
                                    random.uniform(10.0, 50.0),
                                    0,
                                    random.uniform(-math.pi, math.pi),
                                    0)
                self._test_one_pose(morse,
                                    random.uniform(-30.0, 30.0),
                                    random.uniform(-30.0, 30.0),
                                    random.uniform(10.0, 50.0),
                                    0, 0,
                                    random.uniform(-math.pi, math.pi))



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