To receive notifications about scheduled maintenance, please subscribe to the mailing-list gitlab-operations@sympa.ethz.ch. You can subscribe to the mailing-list at https://sympa.ethz.ch

QualisysDataPublisher.py 14.2 KB
Newer Older
1
#!/usr/bin/env python3
2
3
# -*- coding: utf-8 -*-

4
5
# OPTIONS: #!/usr/bin/env python
# OR:      #!/usr/bin/python3
beuchatp's avatar
beuchatp committed
6
# OR:      #!/usr/bin/python3.5
7
8

# WHERE THE KEY INSTALLATIONS TO USE python3 ARE:
9
10
11
12
13
14
15
16
17
# >> sudo apt-get install python3-pip python3-yaml
# >> pip3 install rospkg catkin_pkg --user

# INSTALL THE LATEST VERSION OF QTM
# >> pip3 install qtm --user
#
# OR
#
# For ubuntu 16.04, it is necessary to install an older version of QTM
18
# because of compatibility with Python 3.5.2 versus >3.5.3, the commit
19
20
21
# key from the GitHub repository is:
# qualisys_python_sdk-327bf90e2829e02c40d3d85ed11e6e4d2d25f8a8
#
22
23
# Once downloaded, this can be installed from the local files using:
# pip3 install -e /path/to/folder/containing/setup.py
24
25
#
# Install also the requirements
26
27
# Note: that you may need to remove "black==18.6b4" from the list
# in the "requirements.txt" file pip3 throws an error
28
# >> pip3 install -r /path/to/requirements.txt
29

30
#    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
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
#
#    This file is part of D-FaLL-System.
#    
#    D-FaLL-System is free software: you can redistribute it and/or modify
#    it under the terms of the GNU General Public License as published by
#    the Free Software Foundation, either version 3 of the License, or
#    (at your option) any later version.
#    
#    D-FaLL-System is distributed in the hope that it will be useful,
#    but WITHOUT ANY WARRANTY; without even the implied warranty of
#    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
#    GNU General Public License for more details.
#    
#    You should have received a copy of the GNU General Public License
#    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
#    
#
#    ----------------------------------------------------------------------------------
#    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
#    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
#    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
#    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
#    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
#
#
#    DESCRIPTION:
#    The publisher for the Qualisys motion capture data
#
#    ----------------------------------------------------------------------------------


62

63
# Import ros and the D-FaLL package
64
65
66
67
68
69
70
71
72
73
import roslib; roslib.load_manifest('dfall_pkg')
import rospy

# Import the standard message types
from std_msgs.msg import Int32
from std_msgs.msg import Float32
from std_msgs.msg import String

# Import the D-FaLL message types
from dfall_pkg.msg import ViconData
74
from dfall_pkg.msg import CrazyflieData
75
76
77
78
79
from dfall_pkg.msg import UnlabeledMarker

# General import
import time
import math
80
81
82
83
84
85
86

# Not sure if any of these are required
#import logging
#import datetime
#from enum import Enum
#import sys
#import struct
87

88
89
# ROS imports
#import rosbag
90
91
from rospkg import RosPack

92
93
94
# Import the library for asynchronous I/O
import asyncio

95
96
97
# Import the library for parsing XML trees
import xml.etree.ElementTree as ET

98
99
100
101
102
103
104
# Import the Qualisys Track Manager (QTM) Library
import qtm





105
# DEFINE CONSTANTS
106

107
108
109
# Conversion between radians and degrees
RAD_TO_DEG = 57.296
DEG_TO_RAD = 0.01745329
110

111
# Path to the file with "fake" data for testing QTM
112
113
#QTM_FILE = pkg_resources.resource_filename("qtm", "data/Demo.qtm")
QTM_FILE = "none"
114
115


116
117
118
119
120
121
# OPEN THE ROS BAG FOR WRITING
#rp = RosPack()
#record_file = rp.get_path('dfall_pkg') + '/LoggingOnboard.bag'
#rospy.loginfo('afdsasdfasdfsadfasdfasdfasdfasdfasdfasdf')
#rospy.loginfo(record_file)
#bag = rosbag.Bag(record_file, 'w')
122
123
124
125
126





127
class QualisysQtmClient:
128
129
130
131
132
133
134
135
136
    """
       Qualisys Data Publisher that connects to the
       Qualisys Track Manager (QTM) server, receives
       the 6DOF data, and publishs it for other nodes
       to use.
    """
    def __init__(self):

        # QTM CONNECTION STATUS AND OBJECT
137
        self.qtm_ip = "10.42.00.15:801"
138
139
140
        self._qtm_status = "empty"
        self._qtm_connection = None

141
142
143
144
145
        self._body_to_index_dictionary = None
        self._list_of_body_names = None

        self._qualisys_data_publisher = rospy.Publisher(node_name + '/ViconData', ViconData, queue_size=1)

146
147

        # WAIT FOR A SHORT TIME BEFORE PROCEEDING WITH INITIALISATION
148
        time.sleep(0.1)
149
150

        # Initialize the CrazyFlie and add callbacks
151
        self._init_qtm_client()
152

153
154


155
156
157
158


    # INITIALISE THE QTM CLIENT OBJECT
    def _init_qtm_client(self):
159
160
        # Get the "qtm_host_ip_address" parameter that is the IP address
        self.qtm_ip = rospy.get_param("~qtm_host_ip_address")
161
162
163


    # CONNECT TO THE QTM SERVER
164
165
166
167
    async def connect_to_qtm(self):
        # Inform the user
        print("[QUALISYS DATA PUBLISHER] now attempting to connect to QTM at IP address ", self.qtm_ip )

168
169
        # Connect to QTM
        self._qtm_connection = await qtm.connect( self.qtm_ip )
170

171
172
        # Inform the user is the QTM connection failed
        if self._qtm_connection is None:
173
174
175
176
            print("[QUALISYS DATA PUBLISHER] connection is NONE for IP address = " , self.qtm_ip )
            return

        # Take control of qtm, context manager will automatically release control after scope end
177
        async with qtm.TakeControl(self._qtm_connection, "password"):
178
179
180
181
182
183
184
185
186

            # Specify whether to:
            # True  = get real-time QTM
            # False = get data from file
            get_realtime_data = True

            if get_realtime_data:
                
                # Get the current connection state to the QTM server
187
                current_connection_state = await self._qtm_connection.get_state()
188
189

                # Inform the user of the current connection state
190
                print( "[QUALISYS DATA PUBLISHER] QTM connection State = " , current_connection_state )
191

192
193
194
                # If not currently connected to the QTM serever...
                if (current_connection_state != qtm.QRTEvent.EventConnected):
                    # ... then start new connection to the QTM server
195
                    await self._qtm_connection.new()
196

197
198
            else:
                # Load qtm file
199
                await self._qtm_connection.load(QTM_FILE)
200
201

                # start rtfromfile
202
                await self._qtm_connection.start(rtfromfile=True)
203
204

        # Get 6dof settings from QTM
205
        parameters_6d_as_xml_string = await self._qtm_connection.get_parameters(parameters=["6d"])
206
207
208
209

        # Convert the XML string to a index of the 6DOF bodies available from QTM
        # This should be a dictionary that has the name of the object, and its index,
        # for example: {'CF01',0 , 'CF02',1}
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
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
        self._body_to_index_dictionary = self.create_body_index(parameters_6d_as_xml_string)

        self._list_of_body_names = self.create_list_of_body_names(parameters_6d_as_xml_string)

        print("[QUALISYS DATA PUBLISHER] Index of 6DOF bodies available from QTM: " , self._body_to_index_dictionary )





    # START STREAMING FRAMES RECIEVED FROM QTM
    async def start_streaming(self):
        # Inform the user
        print("[QUALISYS DATA PUBLISHER] Now starting to stream 6DOF data" )
        # Start streaming frames:
        # > with position and rotation matrix
        #await connection.stream_frames(components=["6d"], on_packet=on_6d_packet)
        # > with position and euler angles
        # Take control of qtm, context manager will automatically release control after scope end
        await self._qtm_connection.stream_frames(frames="allframes",components=["6deuler"], on_packet=self.on_6deuler_packet)

        # Options for .stream_frames:
        # frames=| allframes | frequency:n | frequencydivisor:n |
        # where n should be the desired value




    # STOP STREAMING FRAMES RECIEVED FROM QTM
    async def stop_streaming(self):
        # Stop streaming
        await self._qtm_connection.stream_frames_stop()





    def on_6deuler_packet(self,packet):

        # DEBUGGING: Print the frame number
        #print("[DEBUGGING] Framenumber: {}".format(packet.framenumber))

        # GET THE DATA FROM THE PACKET
        #info, bodies = packet.get_6d()
        info, bodies  = packet.get_6d_euler()

        # DEBUGGING: Print the body count and position of an object
        # print("[DEBUGGING] Body count = ", info.body_count )
        # if info.body_count > 0:
        #     position, rotation = bodies[0]
        #     print( "position.x = " , position[0] )

        if info.body_count > 0:

            # Initilise a "ViconData" struct
            # > This is defined in the "ViconData.msg" file
            viconData = ViconData()

            # Initalise a counter for the bodies
            current_body_index = 0

            # Iterate through the bodies
            for body in bodies:
                
                # Get the position and rotation data of the body
                position, rotation = body

                # DEBUGGING: to check the naming of rotation angles
                #print( "rotation = ", rotation )

                # Initialise a "ViconData" struct
                # > This is defined in the "CrazyflieData.msg" file
                this_crazyflie_data = CrazyflieData();

                # Add the name of this object
                if current_body_index < len(self._list_of_body_names):
                    this_crazyflie_data.crazyflieName = self._list_of_body_names[current_body_index]
                else:
                    this_crazyflie_data.crazyflieName = ''

                # Check for "nan" as an indication of occulsion
                if math.isnan(position.x):
                    # Fill in the occlusion flag
                    this_crazyflie_data.occluded = True
                else:
                    # Fill in the occlusion flag
                    this_crazyflie_data.occluded = False

                    # Fill in the position data
299
300
301
                    this_crazyflie_data.x = position.x * 0.001
                    this_crazyflie_data.y = position.y * 0.001
                    this_crazyflie_data.z = position.z * 0.001
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324

                    # Fill in the position data
                    this_crazyflie_data.roll  = rotation.a3 * DEG_TO_RAD
                    this_crazyflie_data.pitch = rotation.a2 * DEG_TO_RAD
                    this_crazyflie_data.yaw   = rotation.a1 * DEG_TO_RAD

                # DEBUGGIN: print out the crazyflie data
                #print(this_crazyflie_data)

                # Add the data for this body to the ViconData struct
                viconData.crazyflies.append(this_crazyflie_data)

                # Increment the indexing
                current_body_index = current_body_index + 1


            # PUBLISH THE VICON DATA
            self._qualisys_data_publisher.publish(viconData)

            # DEBUGGIN:
            #print(viconData)


325
326
327
328



    # EXTRACT THE INDEX DICTIONARY FROM 6DOF SETTING XML
329
    def create_body_index(self, xml_string):
330
331
332
333
334
335
336
337
338
339
340
341
        # Parse the element tree of the XML string
        xml = ET.fromstring(xml_string)

        # Initliase the "body_to_index" return variable
        body_to_index = {}
        # Iterate through the approriate elements of the XML element tree
        for index, body in enumerate(xml.findall("*/Body/Name")):
            # Add the name of this body and its index
            body_to_index[body.text.strip()] = index

        # Return the "body_to_index" variable
        return body_to_index
342
343
344
345
346





347
348
349
350
    # EXTRACT THE INDEX DICTIONARY FROM 6DOF SETTING XML
    def create_list_of_body_names(self, xml_string):
        # Parse the element tree of the XML string
        xml = ET.fromstring(xml_string)
351

352
353
354
355
356
357
        # Initliase the "list_of_names" return variable
        list_of_names = list()
        # Iterate through the approriate elements of the XML element tree
        for index, body in enumerate(xml.findall("*/Body/Name")):
            # Add the name of this body to the list
            list_of_names.append(body.text.strip())
358

359
360
        # Return the "list_of_names" variable
        return list_of_names
361

362

363

364
365
366
367
368


# THIS INITIALISES THE ROS NODE
if __name__ == '__main__':

369
    # STARTING THE ROS-NODE
370
    global node_name
371
    node_name = "ViconDataPublisher"
372
373
    rospy.init_node(node_name, anonymous=True)

374
    # GET THE NAMESPACE OF THIS NODE
375
376
    global ros_namespace
    ros_namespace = rospy.get_namespace()
377
    
378
    # PUBLISHER FOR THE MOTION CAPTURE DATA
379
380
    #global qualisys_data_publisher
    #qualisys_data_publisher = rospy.Publisher(node_name + '/ViconData', ViconData, queue_size=1)
381

382
    # IP ADDRESS OF THE HOST "QUALISYS COMPUTER"
383
384
385
386
    # > This is specified in the "QualisysConfig.yaml" file
    # > That yaml file is added to this node during launch
    # > The "Qualisys Computer" runs the "QTM" software that
    #   is the heart of the Qualisys Motion Capture system
387
388
389
390
391
392
    number_of_fails = 0
    while not rospy.has_param("~qtm_host_ip_address"):
        number_of_fails = number_of_fails + 1 
        if number_of_fails > 9:
            print("[QUALISYS DATA PUBLISHER] ERROR, qtm_host_ip_address parameter not found.")
            number_of_fails = 0;
393
394
395
        time.sleep(0.05)

    #global qtm_ip
396
    qtm_ip = rospy.get_param("~qtm_host_ip_address")
397

398
    print("[QUALISYS DATA PUBLISHER] qtm_host_ip_address parameter = " , qtm_ip )
399
    
400
    # INFORM THE USER
401
402
403
404
405
406
407
408
    #rospy.loginfo("[QUALISYS DATA PUBLISHER] Now attempting to connection to QTM server at IP address: %s", qtm_ip)
    

    # Initialise a "CrazyRadioClient" type variable that handles
    # all communication over the CrazyRadio
    global qtm_client
    qtm_client = QualisysQtmClient()

409
410
411
    # Connect to the QTM server
    asyncio.get_event_loop().run_until_complete( qtm_client.connect_to_qtm() )

412
413


414
    #asyncio.get_event_loop().run_until_complete( qtm_client.start_streaming() )
415

416
417
418
    # Start streaming the data
    asyncio.ensure_future( qtm_client.start_streaming() )
    asyncio.get_event_loop().run_forever()
419
    
420
421
422
423
    # PAUSE FOR A SECOND AND THEN SPIN
    time.sleep(1.0)
    print("[QUALISYS DATA PUBLISHER] Node READY :-)")
    rospy.spin()
424

425
426
    # DISCONNECT FROM THE QTM SERVER
    #print("[QUALISYS DATA PUBLISHER] Disconnecting from QTM server")
427
    #qtm_client.stop_streaming()
428
429
430
431
432
433
434
    
    # Wait for diconnection to complete
    #time.sleep(1.0)
    #print("[QUALISYS DATA PUBLISHER] Disconnected from QTM server")

    # CLOSE THE LOGGING "BAG"
    #bag.close()
435
    #rospy.loginfo("[QUALISYS DATA PUBLISHER] ROS logging bag is closed")