File: waypoint_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 (186 lines) | stat: -rwxr-xr-x 6,364 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
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
#! /usr/bin/env python
"""
This script tests the waypoints actuator, both the data and service api
"""
import logging

import sys
import math
from morse.testing.testing import MorseTestCase
from pymorse import Morse, MorseServicePreempted

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

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

        pose = Pose('pose')
        pose.translate(z=-0.10) # atrv body
        robot.append(pose)
        pose.add_stream('socket')

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

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

    def test_waypoint_datastream(self):
        """ This test is guaranteed to be started only when the simulator
        is ready.
        """
        with Morse() as simu:
        
            # Read the start position, it must be (0.0, 0.0, 0.0)
            pose_stream = simu.robot.pose
            pose = pose_stream.get()
            for key, coord in pose.items():
                if key != 'timestamp':
                    self.assertAlmostEqual(coord, 0.0, delta=0.02)

            # waypoint controller
            motion = simu.robot.motion
            motion.publish({'x' : 4.0, 'y': 2.0, 'z': 0.0, 
                            'tolerance' : 0.5, 
                            'speed' : 1.0})
            simu.sleep(10)

            pose = pose_stream.get()
            self.assertAlmostEqual(pose['x'], 4.0, delta=0.5)
            self.assertAlmostEqual(pose['y'], 2.0, delta=0.5)


            # test tolerance parameter
            motion.publish({'x' : 0.0, 'y': 0.0, 'z': 0.0, 
                            'tolerance' : 1.0, 
                            'speed' : 1.0})
            simu.sleep(10)
            pose = pose_stream.get()
            distance_goal = math.sqrt( pose['x'] * pose['x'] + pose['y'] * pose['y'])
            self.assertLess(distance_goal, 1.0)
            self.assertGreater(distance_goal, 0.5)

    def test_waypoint_services(self):

        with Morse() as simu:
            # Read the start position, it must be (0.0, 0.0, 0.0)
            pose_stream = simu.robot.pose
            pose = pose_stream.get()

            for key, coord in pose.items():
                if key != 'timestamp':
                    self.assertAlmostEqual(coord, 0.0, delta=0.02)

            logger.info("Moving 2m ahead...")

            simu.robot.motion.goto(2.0, 0.0, 0.0, 0.1, 1.0).result() # wait for completion

            pose = pose_stream.get()
            self.assertAlmostEqual(pose['x'], 2.0, delta=0.1)
            self.assertAlmostEqual(pose['y'], 0.0, delta=0.1)
            logger.info("Ok.")

            action = simu.robot.motion.goto(4.0, 0.0, 0.0, 0.1, 1.0) # do not wait for completion
            logger.info("Moving for 1 sec...")
            simu.sleep(1)

            pose = pose_stream.get() #should have done 1m
            self.assertAlmostEqual(pose['x'], 3.0, delta=0.15)
            logger.info("Ok, reached correct position")

            self.assertTrue(action.running())
            self.assertFalse(action.done())

            logger.info("Cancelling motion and waiting for 0.5 sec...")
            action.cancel()
            simu.sleep(0.1)

            self.assertFalse(action.running())
            self.assertTrue(action.done())

            with self.assertRaises(MorseServicePreempted):
                action.result()

            simu.sleep(0.5)
            pose = pose_stream.get() #should not have moved
            self.assertAlmostEqual(pose['x'], 3.0, delta=0.15)
            logger.info("Ok, did not move")

            logger.info("Moving again, waiting for 2 sec, and ensuring the action terminate")
            action = simu.robot.motion.goto(4.0, 0.0, 0.0, 0.1, 1.0) # do not wait for completion
            simu.sleep(2)
            self.assertTrue(action.done())
            self.assertFalse(action.running())

            # Stop will stop the robot, but do not erase current goal
            action = simu.robot.motion.goto(6.0, 0.0, 0.0, 0.1, 1.0) # do not wait for completion
            logger.info("Moving for 1 sec...")
            simu.sleep(1)

            self.assertFalse(action.done())
            self.assertTrue(action.running())

            status = simu.robot.motion.get_status().result()
            self.assertEqual(status, "Transit")

            simu.robot.motion.stop().result()

            # Stop does not change the fact that the goto is pending,
            # but stop the move
            self.assertFalse(action.done())
            self.assertTrue(action.running())

            status = simu.robot.motion.get_status().result()
            self.assertEqual(status, "Stop")

            simu.sleep(0.2)

            pose = pose_stream.get() 
            _x = pose['x']
            self.assertAlmostEqual(pose['x'], 5.2, delta=0.20)

            simu.sleep(0.5)
            pose = pose_stream.get() #should not have moved
            self.assertAlmostEqual(pose['x'], _x, delta=0.03)
            logger.info("Ok, did not move")

            # now resume the move

            simu.robot.motion.resume().result()

            simu.sleep(0.5)

            # must move now
            pose = pose_stream.get()
            self.assertAlmostEqual(pose['x'], 5.7, delta=0.20)
            status = simu.robot.motion.get_status().result()
            self.assertEqual(status, "Transit")

            # wait for the end of the move
            simu.sleep(1.5)
            self.assertTrue(action.done())
            self.assertFalse(action.running())

            pose = pose_stream.get()
            self.assertAlmostEqual(pose['x'], 6.0, delta=0.15)
            status = simu.robot.motion.get_status().result()
            self.assertEqual(status, "Arrived")


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