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
9
10
11
12

# WHERE THE KEY INSTALLATIONS TO USE python3 ARE:
# sudo apt-get install python3-pip python3-yaml
# pip3 install rospkg catkin_pkg --user
# pip3 install qtm --user

13
#    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
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
#
#    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
#
#    ----------------------------------------------------------------------------------


45

46
# Import ros and the D-FaLL package
47
48
49
50
51
52
53
54
55
56
57
58
59
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
from dfall_pkg.msg import UnlabeledMarker

# General import
60
#import logging
61
62
63
64
65
66
67
import time
import datetime
import math
from enum import Enum
import sys
import struct

68
69
# ROS imports
#import rosbag
70
71
from rospkg import RosPack

72
73
74
# Import the library for asynchronous I/O
import asyncio

75
76
77
# Import the library for parsing XML trees
import xml.etree.ElementTree as ET

78
79
80
81
82
83
84
# Import the Qualisys Track Manager (QTM) Library
import qtm





85
# DEFINE CONSTANTS
86

87
88
89
# Conversion between radians and degrees
RAD_TO_DEG = 57.296
DEG_TO_RAD = 0.01745329
90

91
# Path to the file with "fake" data for testing QTM
92
93
#QTM_FILE = pkg_resources.resource_filename("qtm", "data/Demo.qtm")
QTM_FILE = "none"
94
95


96
97
98
99
100
101
# 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')
102
103
104
105
106





107
class QualisysQtmClient:
108
109
110
111
112
113
114
115
116
    """
       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
117
        self.qtm_ip = "10.42.00.15:801"
118
119
120
        self._qtm_status = "empty"
        self._qtm_connection = None

121
122

        # WAIT FOR A SHORT TIME BEFORE PROCEEDING WITH INITIALISATION
123
        time.sleep(0.1)
124
125

        # Initialize the CrazyFlie and add callbacks
126
        self._init_qtm_client()
127
128

        # Connect to the Crazyflie
129
130
        #asyncio.ensure_future( self.connect_to_qtm() )
        asyncio.get_event_loop().run_until_complete( self.connect_to_qtm() )
131
132
133
134


    # INITIALISE THE QTM CLIENT OBJECT
    def _init_qtm_client(self):
135
136
        # Get the "qtm_host_ip_address" parameter that is the IP address
        self.qtm_ip = rospy.get_param("~qtm_host_ip_address")
137
138
139


    # CONNECT TO THE QTM SERVER
140
141
142
143
    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 )

144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
        # Connect to qtm
        connection = await qtm.connect( self.qtm_ip )

        # Inform the user is the connection failed
        if connection is None:
            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
        async with qtm.TakeControl(connection, "password"):

            # 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
                current_connection_state = await connection.get_state()

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

168
169
170
171
                # If not currently connected to the QTM serever...
                if (current_connection_state != qtm.QRTEvent.EventConnected):
                    # ... then start new connection to the QTM server
                    await connection.new()
172

173
174
175
176
177
178
179
180
181
182
183
184
185
            else:
                # Load qtm file
                await connection.load(QTM_FILE)

                # start rtfromfile
                await connection.start(rtfromfile=True)

        # Get 6dof settings from QTM
        parameters_6d_as_xml_string = await connection.get_parameters(parameters=["6d"])

        # 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}
186
        body_to_index_dictionary = self.create_body_index(parameters_6d_as_xml_string)
187

188
        print("[QUALISYS DATA PUBLISHER] Index of 6DOF bodies available from QTM: " , body_to_index_dictionary )
189
190
191


    # EXTRACT THE INDEX DICTIONARY FROM 6DOF SETTING XML
192
    def create_body_index(self, xml_string):
193
194
195
196
197
198
199
200
201
202
203
204
        # 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
205
206
207


    # "on_event" CALLBACK FROM THE "qtm.connect" FUNCTION
208
209
210
211
212
213
214
    # def on_qtm_event(self, event):
    #     logger.info(event)
    #     if event == qtm.QRTEvent.EventRTfromFileStarted:
    #         self.qtmStatus = 'connected'

    #     elif event == qtm.QRTEvent.EventRTfromFileStopped:
    #         self.qtmStatus = 'connected : Waiting QTM to start sending data'
215
216

    # CALLBACK FOR QTM DISCONNECTED
217
218
219
220
    # async def on_qtm_disconnect(self, reason):
    # #def on_qtm_disconnect(self, reason):
    #     # "Clear" the QTM connection object
    #     self._qtm_connection = None
221

222
223
    #     # Log the reason for the disconnection
    #     #logger.info(reason)
224

225
226
227
    #     # Update the QTM status
    #     self.qtmStatus = 'not connected : {}'.format(
    #         reason if reason is not None else '')
228
229
230


    # GETTERS AND SETTERS
231
232
233
234
235
    # @qtmStatus.setter
    # def qtmStatus(self, value):
    #     if value != self._qtm_status:
    #         self._qtm_status = value
    #         rospy.loginfo("[QUALISYS DATA PUBLISHER] QTM Connection status changed to: %s", self._qtm_status)
236
    #         print("[QUALISYS DATA PUBLISHER] QTM Connection status changed to: %s", self._qtm_status)
237
238
239
240




241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
# async def qtm_connect(self, ip):

#     connection = await qtm.connect(
#         ip,
#         on_event=self.on_qtm_event,
#         on_disconnect=lambda reason: start_async_task(
#             self.on_qtm_disconnect(reason)))

#     if connection is None:
#         start_async_task(self.on_qtm_disconnect("Failed to connect"))
#         return

#     self._qtm_connection = connection
#     await self.setup_qtm_connection()

256

257
258
259
# async def setup():
#     """ Main function """
#     connection = await qtm.connect("10.42.0.15")
260

261
262
263
#     if connection is None:
#         print("[QUALISYS DATA PUBLISHER] connection is NONE")
#         return
264
265
266
267
268


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

269
    # STARTING THE ROS-NODE
270
    global node_name
271
    node_name = "ViconDataPublisher"
272
273
    rospy.init_node(node_name, anonymous=True)

274
    # GET THE NAMESPACE OF THIS NODE
275
276
    global ros_namespace
    ros_namespace = rospy.get_namespace()
277
    
278
279
280
281
    # PUBLISHER FOR THE MOTION CAPTURE DATA
    global qualisys_data_publisher
    qualisys_data_publisher = rospy.Publisher(node_name + '/ViconData', ViconData, queue_size=1)

282
    # IP ADDRESS OF THE HOST "QUALISYS COMPUTER"
283
284
285
286
    # > 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
287
288
289
290
291
292
    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;
293
294
295
        time.sleep(0.05)

    #global qtm_ip
296
    qtm_ip = rospy.get_param("~qtm_host_ip_address")
297

298
    print("[QUALISYS DATA PUBLISHER] qtm_host_ip_address parameter = " , qtm_ip )
299
    
300
    # INFORM THE USER
301
302
303
304
305
306
307
308
309
310
    #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()



311

312
    
313
314
315
316
    # PAUSE FOR A SECOND AND THEN SPIN
    time.sleep(1.0)
    print("[QUALISYS DATA PUBLISHER] Node READY :-)")
    rospy.spin()
317

318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
    # DISCONNECT FROM THE QTM SERVER
    #print("[QUALISYS DATA PUBLISHER] Disconnecting from QTM server")
    #cf_client._cf.close_link()
    
    # Wait for diconnection to complete
    #time.sleep(1.0)
    #print("[QUALISYS DATA PUBLISHER] Disconnected from QTM server")

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

    




    #asyncio.ensure_future(setup())
    #asyncio.get_event_loop().run_forever()
337

338
339
    # # ENTER A WHILE LOOP FOR ATTEMPTING TO CONNECT
    # qtm_is_connected = False
340

341
    # while not(qtm_is_connected):
342

343
344
345
346
347
348
349
    #     # ATTEMPT TO CONNECT TO THE QTM MANAGER
    #     connection = await qtm.connect("127.0.0.1")
    #     # connection = await qtm.connect(
    #     #     qtm_ip,
    #     #     on_event=self.on_qtm_event,
    #     #     on_disconnect=lambda reason: start_async_task(
    #     #         self.on_qtm_disconnect(reason)))
350

351
352
353
354
355
356
357
358
359
360
    #     # CHECK IF THE CONNECTION WAS SUCCESSFUL
    #     if connection is None:
    #         # Update the status
    #         start_async_task(self.on_qtm_disconnect("failed to connect"))
    #         # Wait for a second before trying again
    #         time.sleep(1.0)
    #     # ELSE
    #     else:
    #         # Set the flag to exit the while loop
    #         qtm_is_connected = True
361

362
363
364
    # # PUT THE CONNECTION OBJECT INTO "self"
    # self._qtm_connection = connection
    # #await self.setup_qtm_connection()
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440



    

    # # Initialize the low-level drivers (don't list the debug drivers)
    # cflib.crtp.init_drivers(enable_debug_driver=False)

    # #wait until address parameter is set by FlyingAgentClient
    # while not rospy.has_param("~crazyFlieAddress"):
    #     time.sleep(0.05)

    # #use this following two lines to connect without data from CentralManager
    # # radio_address = "radio://0/72/2M"
    # # rospy.loginfo("manual address loaded")

    # # Fetch the YAML paramter "battery polling period"
    # global battery_polling_period
    # battery_polling_period = rospy.get_param(ros_namespace + "/CrazyRadio/battery_polling_period")

    # # Fetch the YAML paramter "agentID" and "coordID"
    # global m_agentID
    # m_agentID = rospy.get_param(ros_namespace + "/FlyingAgentClient/agentID")
    # coordID   = rospy.get_param(ros_namespace + "/FlyingAgentClient/coordID")
    # # Convert the coordinator ID to a zero-padded string
    # coordID_as_string = format(coordID, '03')


    # # Initialise a publisher for the battery voltage
    # global cfbattery_pub
    # cfbattery_pub = rospy.Publisher(node_name + '/CFBattery', Float32, queue_size=10)

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

    # print "[CRAZY RADIO] DEBUG 2"

    # # Subscribe to the commands for when to (dis-)connect the
    # # CrazyRadio connection with the Crazyflie
    # # > For the radio commands from the FlyingAgentClient of this agent
    # rospy.Subscriber("FlyingAgentClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)
    # # > For the radio command from the coordinator
    # rospy.Subscriber("/dfall/coord" + coordID_as_string + "/FlyingAgentClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)


    # # Advertise a Serice for the current status
    # # of the Crazy Radio connect
    # s = rospy.Service(node_name + "/getCurrentCrazyRadioStatus", IntIntService , cf_client.getCurrentCrazyRadioStatusServiceCallback)



    # time.sleep(1.0)

    # rospy.Subscriber("FlyingAgentClient/ControlCommand", ControlCommand, controlCommandCallback)

    # print "[CRAZY RADIO] Node READY :-)"
    # rospy.spin()
    # rospy.loginfo("[CRAZY RADIO] Turning off crazyflie")

    # cf_client._send_to_commander_motor(0, 0, 0, 0)
    # # change state to motors OFF
    # msg = IntWithHeader()
    # msg.shouldCheckForAgentID = False
    # msg.data = CMD_CRAZYFLY_MOTORS_OFF
    # cf_client.FlyingAgentClient_command_pub.publish(msg)
    # #wait for client to send its commands
    # time.sleep(1.0)


    # bag.close()
    # rospy.loginfo("[CRAZY RADIO] bag closed")

    # cf_client._cf.close_link()
    # rospy.loginfo("[CRAZY RADIO] Link closed")