-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathuwb_pub.py
182 lines (152 loc) · 7.53 KB
/
uwb_pub.py
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
#!/usr/bin/env python
"""
The Pozyx ready to localize tutorial (c) Pozyx Labs
Please read the tutorial that accompanies this sketch:
https://www.pozyx.io/Documentation/Tutorials/ready_to_localize/Python
This tutorial requires at least the contents of the Pozyx Ready to Localize kit. It demonstrates the positioning capabilities
of the Pozyx device both locally and remotely. Follow the steps to correctly set up your environment in the link, change the
parameters and upload this sketch. Watch the coordinates change as you move your device around!
"""
import rospy
from time import sleep
import time
from geometry_msgs.msg import PointStamped,Point
from pypozyx import *
from pythonosc.osc_message_builder import OscMessageBuilder
from pythonosc.udp_client import SimpleUDPClient
posdata=[[0,0,0],[0,0,0],[0,0,0]]
realdata=[[0,0,0],[0,0,0],[0,0,0]]
startPos=[0,0,0]
a=[1,-1.279632424997809,0.477592250072517]
b=[0.049489956268677,0.098979912537354,0.049489956268677]
#a=[1,-1.705552145544084,0.743655195048866]
#b=[0.009525762376195,0.019051524752391,0.009525762376195]
N=1000
i=0
DT=0
class ReadyToLocalize(object):
"""Continuously calls the Pozyx positioning function and prints its position."""
def pos_pub(self):
pub = rospy.Publisher('uwb_pos', Point, queue_size=1)
rospy.init_node('talker', anonymous=True)
while not rospy.is_shutdown():
position = Coordinates()
status = self.pozyx.doPositioning(position, self.dimension, self.height, self.algorithm, remote_id=self.remote_id)
#curr_pos=Point(posdata[0][0]/1000.0,posdata[0][1]/1000.0,posdata[0][2]/1000.0)
#print(" x=%f , y=%f ,z=%f \n" % (posdata[0][0]/1000.0,posdata[0][1]/1000.0,posdata[0][2]/1000.0))
curr_pos=Point(position.x/1000.0,position.y/1000.0,position.z/1000.0)
pub.publish(curr_pos)
def __init__(self, pozyx, osc_udp_client, anchors, algorithm=POZYX_POS_ALG_TRACKING, dimension=POZYX_3D, height=1000, remote_id=None):
self.pozyx = pozyx
self.osc_udp_client = osc_udp_client
self.anchors = anchors
self.algorithm = algorithm
self.dimension = dimension
self.height = height
self.remote_id = remote_id
def setup(self):
pos_error=0
"""Sets up the Pozyx for positioning by calibrating its anchor list."""
print("------------POZYX POSITIONING V1.1 -------------")
print("NOTES: ")
print("- No parameters required.")
print()
print("- System will auto start configuration")
print()
print("- System will auto start positioning")
print()
self.pozyx.printDeviceInfo(self.remote_id)
print()
print("------------POZYX POSITIONING V1.1 --------------")
print()
self.pozyx.clearDevices(self.remote_id)
self.setAnchorsManual()
self.printPublishConfigurationResult()
self.pozyx.setPositionFilter(FILTER_TYPE_MOVINGAVERAGE,0xA)
# self.pozyx.setRangingProtocol(0x0)
def setAnchorsManual(self):
"""Adds the manually measured anchors to the Pozyx's device list one for one."""
status = self.pozyx.clearDevices(self.remote_id)
for anchor in self.anchors:
status &= self.pozyx.addDevice(anchor, self.remote_id)
if len(self.anchors) > 4:
status &= self.pozyx.setSelectionOfAnchors(POZYX_ANCHOR_SEL_AUTO, len(self.anchors))
return status
def printPublishConfigurationResult(self):
"""Prints and potentially publishes the anchor configuration result in a human-readable way."""
list_size = SingleRegister()
status = self.pozyx.getDeviceListSize(list_size, self.remote_id)
print("List size: {0}".format(list_size[0]))
if list_size[0] != len(self.anchors):
self.printPublishErrorCode("configuration")
return
device_list = DeviceList(list_size=list_size[0])
status = self.pozyx.getDeviceIds(device_list, self.remote_id)
print("Calibration result:")
print("Anchors found: {0}".format(list_size[0]))
print("Anchor IDs: ", device_list)
for i in range(list_size[0]):
anchor_coordinates = Coordinates()
status = self.pozyx.getDeviceCoordinates(
device_list[i], anchor_coordinates, self.remote_id)
print("ANCHOR, 0x%0.4x, %s" % (device_list[i], str(anchor_coordinates)))
if self.osc_udp_client is not None:
self.osc_udp_client.send_message(
"/anchor", [device_list[i], int(anchor_coordinates.x), int(anchor_coordinates.y), int(anchor_coordinates.z)])
sleep(0.025)
def printPublishAnchorConfiguration(self):
"""Prints and potentially publishes the anchor configuration"""
for anchor in self.anchors:
print("ANCHOR,0x%0.4x,%s" % (anchor.network_id, str(anchor.coordinates)))
if self.osc_udp_client is not None:
self.osc_udp_client.send_message(
"/anchor", [anchor.network_id, int(anchor_coordinates.x), int(anchor_coordinates.y), int(anchor_coordinates.z)])
sleep(0.025)
if __name__ == "__main__":
# shortcut to not have to find out the port yourself
serial_port = get_first_pozyx_serial_port()
if serial_port is None:
print("No Pozyx connected. Check your USB cable or your driver!")
quit()
remote_id = 0x6069 # remote device network ID
remote = False # whether to use a remote device
if not remote:
remote_id = None
use_processing = True # enable to send position data through OSC
ip = "127.0.0.1" # IP for the OSC UDP
network_port = 8888 # network port for the OSC UDP
osc_udp_client = None
if use_processing:
osc_udp_client = SimpleUDPClient(ip, network_port)
# necessary data for calibration, change the IDs and coordinates yourself
anchors = [DeviceCoordinates(0x6e4e, 1, Coordinates(10940 , 0 ,1490)),
DeviceCoordinates(0x6e2d, 1, Coordinates(2660 , 5250,1125)),
DeviceCoordinates(0x6e32, 1, Coordinates(5050, 0,160)),
DeviceCoordinates(0x6e56, 1, Coordinates(13430, 2700, 1110)),
DeviceCoordinates(0x6e1a, 1, Coordinates(0, 0,2220)),
DeviceCoordinates(0x6e37, 1, Coordinates(7880,5300,1125))]
# anchors = [DeviceCoordinates(0x6e2d, 1, Coordinates(2500,3880,1760)),
# DeviceCoordinates(0x6e56, 1, Coordinates(6000 , 1000,1100)),
# DeviceCoordinates(0x6e37, 1, Coordinates(4075 , 0 ,1490)),
# DeviceCoordinates(0x6e1a, 1, Coordinates(560, 1305, 900)),
# DeviceCoordinates(0x6e4e, 1, Coordinates(4390, 3880,1500)),
# DeviceCoordinates(0x6e32, 1, Coordinates(2200,1200,1400))]
algorithm = POZYX_POS_ALG_UWB_ONLY # positioning algorithm to use
dimension = POZYX_2D # positioning dimension
height = 1000 # height of device, required in 2.5D positioning
pozyx = PozyxSerial(serial_port)
r = ReadyToLocalize(pozyx, osc_udp_client, anchors, algorithm, dimension, height, remote_id)
r.setup()
i=0
start=time.time()
while True:
try:
r.pos_pub()
except rospy.ROSInterruptException:
pass
i=i+1
if(i%100==0):
print("Frequency")
stopt=time.time()
print(100.0/(stopt-start))
start=time.time()