File: armature_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 (272 lines) | stat: -rwxr-xr-x 11,050 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
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
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
#! /usr/bin/env python
"""
This script tests the KUKA LWR arm, both the data and service api
"""

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

# 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

JOINTS = ['kuka_1', 'kuka_2', 'kuka_3', 'kuka_4', 'kuka_5', 'kuka_6', 'kuka_7']

class ArmatureTest(MorseTestCase):
    def setUpEnv(self):
        """ Defines the test scenario, using the Builder API.
        """

        robot = FakeRobot()

        arm = KukaLWR()
        robot.append(arm)
        arm.add_stream('socket')
        arm.add_service('socket')

        pose = Pose()
        pose.add_stream('socket')
        pose.translate(z=1.3105)
        arm.append(pose)

        arm_pose = ArmaturePose()
        arm.append(arm_pose)
        arm_pose.add_stream('socket')

        motion = Teleport()
        robot.append(motion)
        motion.add_service('socket')

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

    def _check_state(self, simu, angles, precision = 0.050):

        pose = simu.robot.arm.arm_pose.get()
        target = dict(zip(JOINTS, angles))

        for j, v in pose.items():
            if j != 'timestamp':
                self.assertAlmostEqual(v, target[j], delta=precision)

    def _check_pose(self, simu, x, y, z, pitch, precision = 0.01):
            self.assertAlmostEqual(simu.robot.arm.pose.get()['x'], x, delta = precision)
            self.assertAlmostEqual(simu.robot.arm.pose.get()['y'], y, delta = precision)
            self.assertAlmostEqual(simu.robot.arm.pose.get()['z'], z, delta = precision)
            self.assertAlmostEqual(simu.robot.arm.pose.get()['pitch'], pitch, delta = precision)


    def test_joints_names(self):
        with Morse() as simu:
            self.assertEquals(simu.robot.arm.get_joints(), JOINTS)

    def test_object_attach(self):
        """ Checks that attached object are indeed attached at the right place.
        """
        precision = 0.02

        with Morse() as simu:

            self._check_pose(simu, 0., 0., 1.3105, 0.)
            simu.robot.motion.translate(1.0)
            simu.sleep(0.1)
            self._check_pose(simu, 1., 0., 1.3105, 0.)
            simu.robot.arm.set_rotation("kuka_2", math.radians(-90)).result()
            simu.sleep(0.1)
            self._check_pose(simu, 2., 0., 0.3105, math.radians(90))

    def test_immediate_api(self):
        """ Tests the services that have an immediate result
        (no speed limit taken into account)

        """
        # TODO: check translations!

        precision = 0.02

        with Morse() as simu:
            simu.robot.arm.set_rotation("kuka_2", 1).result() # basic rotation
            simu.sleep(0.1)
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_2"], 1.0, delta = precision)

            simu.robot.arm.set_rotation("kuka_2", 4000).result() # rotation clamping
            simu.sleep(0.1)
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_2"], 2.09, delta = precision)

            res = simu.robot.arm.set_rotation('pipo',0) # inexistant joint
            self.assertEqual(type(res.exception(1)), MorseServiceFailed)

            res = simu.robot.arm.set_translation('kuka_2',0) # non prismatic joint
            self.assertEqual(type(res.exception(1)), MorseServiceFailed)


            # note that set_rotations is tested in armature_pose_testing

    def test_motion_services(self):
        """ Tests the services that have take some time to move
        (joint speed limit taken into account)
        """
        # TODO: check translations!

        precision = 0.02
        with Morse() as simu:
            simu.robot.arm.rotate("kuka_2", 0.5).result() # basic rotation
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_2"], 0.5, delta = precision)
            simu.robot.arm.rotate("kuka_2", 4000).result() # rotation clamping
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_2"], 2.09, delta = precision)

            res = simu.robot.arm.rotate('pipo',0) # inexistant joint
            self.assertEqual(type(res.exception(1)), MorseServiceFailed)

            res = simu.robot.arm.translate('kuka_2',0) # non prismatic joint
            self.assertEqual(type(res.exception(1)), MorseServiceFailed)

            simu.robot.arm.set_rotation("kuka_2", 0).result() # back to origin
            act = simu.robot.arm.rotate("kuka_2", 1, 0.5)
            self.assertFalse(act.done())
            simu.sleep(1)
            self.assertFalse(act.done())
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_2"], 0.5, delta = precision)
            simu.sleep(1.1)
            self.assertTrue(act.done())

            kuka_4 = simu.robot.arm.arm_pose.get()["kuka_4"]
            simu.robot.arm.rotate_joints({"kuka_2": 0.5, "kuka_3" : 0.2}).result()
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_2"], 0.5, delta = precision)
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_3"], 0.2, delta = precision)
            self.assertAlmostEqual(simu.robot.arm.arm_pose.get()["kuka_4"], kuka_4, delta = precision)

    def test_trajectory(self):

        traj0 = {'points': [
                    {'position': [0.0, 1.57, 0.0, 0.0, 0.0, 0.0, 0.0],
                     'time_from_start': 1.0}
                    ]
                }

        traj1 = {'points': [
                    {'positions': [0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0],
                     'time_from_start': 1.0},
                    {'positions': [0.0, 1.57, 0.0, -1.57, 0.0, 1.57, 0.0],
                     'time_from_start': 4.0},
                    {'positions': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
                     'time_from_start': 6.0}
                    ]
                }

        with Morse() as simu:

            act = simu.robot.arm.trajectory(traj0)
            self.assertEqual(type(act.exception(1)), MorseServiceFailed) # typo in trajectory ('position' instead of 'positions')
            self.assertIn('positions', str(act.exception()))

            act = simu.robot.arm.trajectory(traj1)
            simu.sleep(1)
            self._check_state(simu, [0.0, 1.0, 0,0,0,0,0])
            simu.sleep(3)
            self._check_state(simu, [0.0, 1.57, 0, -1.57, 0, 1.57, 0])
            simu.sleep(2)
            self._check_state(simu, [0.0] * 7)
            simu.sleep(1)
            self._check_state(simu, [0.0] * 7)

            # check 'starttime' parameter
            act = simu.robot.arm.set_rotations([0.0] * 7)
            traj2 = {'starttime': simu.time() + 1,
                    'points': [
                        {'positions': [0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0],
                        'time_from_start': 1.0}
                        ]
                    }

            act = simu.robot.arm.trajectory(traj2)
            simu.sleep(0.5)
            self._check_state(simu, [0.0] * 7)
            simu.sleep(0.5)
            simu.sleep(1)
            self._check_state(simu, [0.0, 1.0, 0,0,0,0,0])
            simu.sleep(1)
            self._check_state(simu, [0.0, 1.0, 0,0,0,0,0])

            # Check action cancellation
            act = simu.robot.arm.set_rotations([0.0] * 7)

            traj2['starttime'] = simu.time() + 1
            act = simu.robot.arm.trajectory(traj2)
            simu.sleep(0.5)
            act.cancel()
            simu.sleep(1)
            self._check_state(simu, [0.0] * 7)

    def test_ik_immediate(self):

        IK_TARGET = "ik_target.robot.arm.kuka_7"

        with Morse() as simu:
            self.assertEqual(simu.robot.arm.list_IK_targets(), [IK_TARGET])
            self._check_pose(simu, 0., 0., 1.3105, 0.)

            simu.robot.arm.place_IK_target(IK_TARGET, [0,0,2], None, False) # absolute location
            simu.sleep(0.1)
            self._check_pose(simu, 0., 0., 1.3105, 0.)

            simu.robot.arm.place_IK_target(IK_TARGET, [1,0,0.3105], None, False)
            simu.sleep(1) # with iterative IK solvers like iTaSC, the IK chain does not reach the end position immediately
            self._check_pose(simu, 0.778, 0., 0.363, 0.02)

            simu.robot.arm.place_IK_target(IK_TARGET, [1,0,0.3105], [math.pi/2, -math.pi/2, -math.pi], False) # arm should be horizontal
            simu.sleep(1) # with iterative IK solvers like iTaSC, the IK chain does not reach the end position immediately
            self._check_pose(simu, 1.0, 0., 0.3105, math.radians(90))

            # back to original position
            simu.robot.arm.place_IK_target(IK_TARGET, [0,0,2], [math.pi/2, 0., -math.pi], False) # absolute location
            simu.sleep(1.)
            self._check_pose(simu, 0., 0., 1.3105, 0.)

            simu.robot.arm.place_IK_target(IK_TARGET, [-1, 0, -1.6895], None) # relative position
            simu.sleep(1) # with iterative IK solvers like iTaSC, the IK chain does not reach the end position immediately
            self._check_pose(simu, -0.778, 0., 0.363, -0.02)

            simu.robot.arm.place_IK_target(IK_TARGET, [0.,0.,0.], [0., -math.pi/2, 0.]) # relative rotation
            simu.sleep(1) # with iterative IK solvers like iTaSC, the IK chain does not reach the end position immediately
            self._check_pose(simu, -1.0, 0., 0.3105, -math.radians(90))




    def test_ik_motion(self):

        IK_TARGET = "ik_target.robot.arm.kuka_7"

        with Morse() as simu:
            self.assertEqual(simu.robot.arm.list_IK_targets(), [IK_TARGET])
            self._check_pose(simu, 0., 0., 1.3105, 0.)

            simu.robot.arm.move_IK_target(IK_TARGET, [0,0,2], None, False).result() # absolute location
            self._check_pose(simu, 0., 0., 1.3105, 0.)

            simu.robot.arm.move_IK_target(IK_TARGET, [1,0,0.3105], None, False).result()
            self._check_pose(simu, 0.778, 0., 0.363, 0.02)

            simu.robot.arm.move_IK_target(IK_TARGET, [1,0,0.3105], [math.pi/2, -math.pi/2, -math.pi], False).result() # arm should be horizontal
            self._check_pose(simu, 1.0, 0., 0.3105, math.radians(90))

            # back to original position
            simu.robot.arm.move_IK_target(IK_TARGET, [0,0,2], [math.pi/2, 0., -math.pi], False).result() # absolute location
            self._check_pose(simu, 0., 0., 1.3105, 0.)

            simu.robot.arm.move_IK_target(IK_TARGET, [-1, 0, -1.6895], None).result() # relative position
            self._check_pose(simu, -0.778, 0., 0.363, -0.02)

            simu.robot.arm.move_IK_target(IK_TARGET, [0.,0.,0.], [0., -math.pi/2, 0.]).result() # relative rotation
            self._check_pose(simu, -1.0, 0., 0.3105, -math.radians(90))

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