tracker.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 
3 import roslib; roslib.load_manifest('people_velocity_tracker')
4 import rospy
5 from geometry_msgs.msg import Point, Vector3
6 import math
7 from people_msgs.msg import PositionMeasurementArray, Person, People
8 from easy_markers.generator import MarkerGenerator, Marker
9 from kalman_filter import Kalman
10 
11 def distance(leg1, leg2):
12  return math.sqrt(math.pow(leg1.x - leg2.x, 2) +
13  math.pow(leg1.y - leg2.y, 2) +
14  math.pow(leg1.z - leg2.z, 2))
15 
16 def average(leg1, leg2):
17  return Point((leg1.x + leg2.x) / 2,
18  (leg1.y + leg2.y) / 2,
19  (leg1.z + leg2.z) / 2)
20 
21 def add(v1, v2):
22  return Vector3(v1.x + v2.x, v1.y + v2.y, v1.z + v2.z)
23 
24 def subtract(v1, v2):
25  return Vector3(v1.x - v2.x, v1.y - v2.y, v1.z - v2.z)
26 
27 def scale(v, s):
28  v.x *= s
29  v.y *= s
30  v.z *= s
31 
32 def printv(v):
33  print "%.2f %.2f %.2f"%(v.x, v.y, v.z),
34 
36 gen.type = Marker.ARROW
37 gen.ns = 'velocities'
38 gen.lifetime = .5
39 
40 
41 class PersonEstimate(object):
42  def __init__(self, msg):
43  self.pos = msg
44  self.reliability = 0.1
45  self.k = Kalman()
46 
47  def update(self, msg):
48  last = self.pos
49  self.pos = msg
50  self.reliability = max(self.reliability, msg.reliability)
51 
52  ivel = subtract(self.pos.pos, last.pos)
53  time = (self.pos.header.stamp - last.header.stamp).to_sec()
54  scale(ivel, 1.0 / time)
55 
56  self.k.update([ivel.x, ivel.y, ivel.z])
57 
58  def age(self):
59  return self.pos.header.stamp
60 
61  def id(self):
62  return self.pos.object_id
63 
64  def velocity(self):
65  k = self.k.values()
66  if k == None:
67  return Vector3()
68  v = Vector3(k[0], k[1], k[2])
69  return v
70 
71  def publish_markers(self, pub):
72  gen.scale = [.1, .3, 0]
73  gen.color = [1, 1, 1, 1]
74  vel = self.velocity()
75  #scale(vel, 15)
76  m = gen.marker(points=[self.pos.pos, add(self.pos.pos, vel)])
77  m.header = self.pos.header
78  pub.publish(m)
79 
80  def get_person(self):
81  p = Person()
82  p.name = self.id()
83  p.position = self.pos.pos
84  p.velocity = self.velocity()
85  p.reliability = self.reliability
86  return self.pos.header.frame_id, p
87 
88 
89 class VelocityTracker(object):
90  def __init__(self):
91  self.people = {}
92  self.TIMEOUT = rospy.Duration(rospy.get_param('~timeout', 1.0))
93  self.sub = rospy.Subscriber('/people_tracker_measurements',
94  PositionMeasurementArray,
95  self.pm_cb)
96  self.mpub = rospy.Publisher('/visualization_marker',
97  Marker,
98  queue_size=10)
99  self.ppub = rospy.Publisher('/people',
100  People,
101  queue_size=10)
102 
103  def pm_cb(self, msg):
104  for pm in msg.people:
105  if pm.object_id in self.people:
106  self.people[pm.object_id].update(pm)
107  else:
108  p = PersonEstimate(pm)
109  self.people[pm.object_id] = p
110 
111  def spin(self):
112  rate = rospy.Rate(10)
113  while not rospy.is_shutdown():
114  # Remove People Older Than timeout param
115  now = rospy.Time.now()
116  for p in self.people.values():
117  if now - p.age() > self.TIMEOUT:
118  del self.people[p.id()]
119  self.publish()
120  rate.sleep()
121 
122  def publish(self):
123  gen.counter = 0
124  pl = People()
125  pl.header.frame_id = None
126 
127  for p in self.people.values():
128  p.publish_markers(self.mpub)
129  frame, person = p.get_person()
130  pl.header.frame_id = frame
131  pl.people.append(person)
132 
133  self.ppub.publish(pl)
134 
135 rospy.init_node("people_velocity_tracker")
137 vt.spin()
def __init__(self, msg)
Definition: tracker.py:42
def update(self, msg)
Definition: tracker.py:47
def get_person(self)
Definition: tracker.py:80
def average(leg1, leg2)
Definition: tracker.py:16
def distance(leg1, leg2)
Definition: tracker.py:11
def add(v1, v2)
Definition: tracker.py:21
def subtract(v1, v2)
Definition: tracker.py:24
def scale(v, s)
Definition: tracker.py:27
def __init__(self)
Definition: tracker.py:90
def publish_markers(self, pub)
Definition: tracker.py:71
def printv(v)
Definition: tracker.py:32
def pm_cb(self, msg)
Definition: tracker.py:103
def velocity(self)
Definition: tracker.py:64


people_velocity_tracker
Author(s): David V. Lu!!
autogenerated on Fri Jun 7 2019 22:07:54