File: destination_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 (124 lines) | stat: -rwxr-xr-x 4,682 bytes parent folder | download | duplicates (3)
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
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
#! /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
from pymorse import Morse

def send_goal(s, x, y, z):
    s.publish({'x' : x, 'y' : y, 'z' : z})

class DestinationTest(MorseTestCase):

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

        destination = Destination('destination')
        robot.append(destination)
        destination.add_stream('socket')
        destination.properties(Speed=2.0, Tolerance=0.3, RemainAtDestination = True)

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

    def test(self):
        with Morse() as morse:
            pose_stream = morse.robot.pose

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

            dest_client = morse.robot.destination
            send_goal(dest_client, 10.0, 0.0, 20.0)

            morse.sleep(3.0)
            # Only x has changed. Check that speed is respected

            pose = pose_stream.get()
            self.assertAlmostEqual(pose['yaw'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['pitch'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['roll'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['x'], 3.0 * 2.0, delta=0.1)
            self.assertAlmostEqual(pose['y'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['z'], 20.0, delta=0.1)

            morse.sleep(2.0)
            # Only x has changed
            pose = pose_stream.get()
            self.assertAlmostEqual(pose['yaw'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['pitch'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['roll'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['x'], 9.7, delta=0.1)
            self.assertAlmostEqual(pose['y'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['z'], 20.0, delta=0.1)

            x = pose['x']
            send_goal(dest_client, x, 10.0, 20.0)
            morse.sleep(5.0)

            # Only Y has changed
            pose = pose_stream.get()
            self.assertAlmostEqual(pose['yaw'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['pitch'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['roll'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['x'], x, delta=0.1)
            self.assertAlmostEqual(pose['y'], 9.7, delta=0.1)
            self.assertAlmostEqual(pose['z'], 20.0, delta=0.1)


            x = pose['x']
            y = pose['y']
            z = pose['z']

            send_goal(dest_client, x, y, 30.0)
            morse.sleep(5.0)

            # Only Z has changed
            # XXX precision is not really good
            pose = pose_stream.get()
            self.assertAlmostEqual(pose['yaw'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['pitch'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['roll'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['x'], x, delta=precision)
            self.assertAlmostEqual(pose['y'], y, delta=precision)
            self.assertAlmostEqual(pose['z'], 30.0, delta=0.3)

            send_goal(dest_client, 0, 0, 20)
            morse.sleep(10.0)
            pose = pose_stream.get()
            self.assertAlmostEqual(pose['yaw'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['pitch'], 0.0, delta=precision)
            self.assertAlmostEqual(pose['roll'], 0.0, delta=precision)
            self.assertLess(math.fabs(pose['x']), 0.3)
            self.assertLess(math.fabs(pose['y']), 0.3)
            self.assertLess(math.fabs(pose['z'] - 20), 0.3)


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