3 import roslib; roslib.load_manifest(
'people_velocity_tracker')
5 from geometry_msgs.msg
import Point, Vector3
7 from people_msgs.msg
import PositionMeasurementArray, Person, People
9 from kalman_filter
import Kalman
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))
17 return Point((leg1.x + leg2.x) / 2,
18 (leg1.y + leg2.y) / 2,
19 (leg1.z + leg2.z) / 2)
22 return Vector3(v1.x + v2.x, v1.y + v2.y, v1.z + v2.z)
25 return Vector3(v1.x - v2.x, v1.y - v2.y, v1.z - v2.z)
33 print "%.2f %.2f %.2f"%(v.x, v.y, v.z),
36 gen.type = Marker.ARROW
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)
56 self.k.update([ivel.x, ivel.y, ivel.z])
59 return self.pos.header.stamp
62 return self.pos.object_id
68 v = Vector3(k[0], k[1], k[2])
72 gen.scale = [.1, .3, 0]
73 gen.color = [1, 1, 1, 1]
76 m = gen.marker(points=[self.pos.pos,
add(self.pos.pos, vel)])
77 m.header = self.pos.header
83 p.position = self.pos.pos
86 return self.pos.header.frame_id, p
92 self.
TIMEOUT = rospy.Duration(rospy.get_param(
'~timeout', 1.0))
93 self.
sub = rospy.Subscriber(
'/people_tracker_measurements',
94 PositionMeasurementArray,
96 self.
mpub = rospy.Publisher(
'/visualization_marker',
99 self.
ppub = rospy.Publisher(
'/people',
104 for pm
in msg.people:
105 if pm.object_id
in self.
people:
106 self.
people[pm.object_id].update(pm)
109 self.
people[pm.object_id] = p
112 rate = rospy.Rate(10)
113 while not rospy.is_shutdown():
115 now = rospy.Time.now()
116 for p
in self.people.values():
117 if now - p.age() > self.
TIMEOUT:
125 pl.header.frame_id =
None 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)
133 self.ppub.publish(pl)
135 rospy.init_node(
"people_velocity_tracker")
def publish_markers(self, pub)