File: xyw_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 (81 lines) | stat: -rwxr-xr-x 2,748 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
#! /usr/bin/env python
"""
This script tests some of the base functionalities of MORSE.
"""

import sys
import math
from morse.testing.testing import MorseMoveTestCase
from pymorse import Morse

# 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

def send_speed(s, morse, x, y, w, t):
    s.publish({'x' : x, 'y' : y, 'w' : w})
    morse.sleep(t + 0.1)
    s.publish({'x' : 0.0, 'y' : 0.0, 'w' : 0.0})

class XYW_Test(MorseMoveTestCase):
    def setUpEnv(self):
        """ Defines the test scenario, using the Builder API.
        """
        robot = ATRV()

        pose = Pose()
        robot.append(pose)
        pose.add_stream('socket')

        motion = MotionXYW('motion')
        robot.append(motion)
        motion.add_stream('socket')
        motion.add_service('socket')

        teleport = Teleport()
        robot.append(teleport)
        teleport.add_stream('socket')
        
        env = Environment('empty', fastmode = True)
        env.add_service('socket')

    def test_xyw_controller(self):
        with Morse() as morse:

            morse.deactivate('robot.teleport')
            xyw = morse.robot.motion

            precision = 0.12

            # Read the start position, it must be (0.0, 0.0, 0.0)
            self.assertAlmostEqualPositionThenFix(morse, [0.0, 0.0, 0.10, 0.0, 0.0, 0.0], precision)

            send_speed(xyw, morse, 1.0, 0.0, 0.0, 2.0)
            self.assertAlmostEqualPositionThenFix(morse, [2.0, 0.0, 0.10, 0.0, 0.0, 0.0], precision)

            send_speed(xyw, morse, 0.0, -1.0, 0.0, 2.0)
            self.assertAlmostEqualPositionThenFix(morse, [2.0, -2.0, 0.10, 0.0, 0.0, 0.0], precision)

            send_speed(xyw, morse, -1.0, 1.0, 0.0, 2.0)
            self.assertAlmostEqualPositionThenFix(morse, [0.0, 0.0, 0.10, 0.0, 0.0, 0.0], precision)

            send_speed(xyw, morse, 1.0, 0.0, -math.pi/4.0, 2.0)
            self.assertAlmostEqualPositionThenFix(morse, [4.0 / math.pi, -4.0 / math.pi, 0.10,
                                 -math.pi / 2.0, 0.0, 0.0], precision)


            send_speed(xyw, morse, 0.5, 0.0, -math.pi/8.0, 12.0)
            self.assertAlmostEqualPositionThenFix(morse, [0.0, 0.0, 0.10, 0.0, 0.0, 0.0], precision)

            send_speed(xyw, morse, -2.0, 0.0, math.pi/2.0, 3.0)
            self.assertAlmostEqualPositionThenFix(morse, [4.0 / math.pi, -4.0 / math.pi, 0.10,
                                 -math.pi / 2.0, 0.0, 0.0], precision*2)


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