Luis Yoichi Morales commited on
Commit
ea2ebdb
·
1 Parent(s): 87aa606

adding a subscriber for testing

Browse files
keypoint-db/ws/src/db_loader/db_loader/keypoint_subscriber.py ADDED
@@ -0,0 +1,158 @@
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
+ #!/usr/bin/env python3
2
+
3
+ """
4
+ Example ROS2 subscriber for skeleton keypoints published by keypoint_publisher.py
5
+
6
+ This script demonstrates how to subscribe to and process the keypoint data.
7
+ The keypoints are published as JSON on the /skeleton_keypoints topic.
8
+ """
9
+
10
+ import rclpy
11
+ from rclpy.node import Node
12
+ from std_msgs.msg import String
13
+ import json
14
+
15
+
16
+ class KeypointSubscriberExample(Node):
17
+ def __init__(self):
18
+ super().__init__('keypoint_subscriber_example')
19
+
20
+ # Subscribe to keypoint data (JSON format)
21
+ self.keypoints_sub = self.create_subscription(
22
+ String,
23
+ 'skeleton_keypoints',
24
+ self.keypoints_callback,
25
+ 10
26
+ )
27
+
28
+ self.get_logger().info('Keypoint subscriber started')
29
+ self.get_logger().info('Listening to: /skeleton_keypoints (JSON)')
30
+
31
+ def keypoints_callback(self, msg):
32
+ """Handle JSON messages containing all keypoint data"""
33
+ try:
34
+ data = json.loads(msg.data)
35
+
36
+ person_id = data['person_id']
37
+ timestamp = data['timestamp']
38
+ keypoints = data['keypoints']
39
+
40
+ self.get_logger().info(f'\n=== Person {person_id} at t={timestamp:.2f}s ===')
41
+ self.get_logger().info(f'Total keypoints: {len(keypoints)}')
42
+
43
+ # Example 1: Print all keypoints
44
+ for kpt in keypoints:
45
+ name = kpt['name']
46
+ pos = kpt['position']
47
+ self.get_logger().info(
48
+ f' {name:20s}: ({pos["x"]:7.3f}, {pos["y"]:7.3f}, {pos["z"]:7.3f})'
49
+ )
50
+
51
+ except json.JSONDecodeError as e:
52
+ self.get_logger().error(f'Failed to parse JSON: {e}')
53
+ except KeyError as e:
54
+ self.get_logger().error(f'Missing expected field: {e}')
55
+
56
+
57
+ class KeypointProcessor(Node):
58
+ """
59
+ More advanced example that processes keypoint data to compute useful metrics
60
+ """
61
+ def __init__(self):
62
+ super().__init__('keypoint_processor')
63
+
64
+ self.keypoints_sub = self.create_subscription(
65
+ String,
66
+ 'skeleton_keypoints',
67
+ self.process_keypoints,
68
+ 10
69
+ )
70
+
71
+ self.get_logger().info('Keypoint processor started')
72
+
73
+ def process_keypoints(self, msg):
74
+ """Process keypoint data to compute useful metrics"""
75
+ try:
76
+ data = json.loads(msg.data)
77
+
78
+ # Convert list of keypoints to a dictionary for easier access
79
+ keypoints = {kpt['name']: kpt['position'] for kpt in data['keypoints']}
80
+
81
+ person_id = data['person_id']
82
+
83
+ # Example 1: Calculate person height (neck to ankle distance)
84
+ if 'neck' in keypoints and 'right_ankle' in keypoints:
85
+ neck = keypoints['neck']
86
+ ankle = keypoints['right_ankle']
87
+
88
+ height = ((neck['x'] - ankle['x'])**2 +
89
+ (neck['y'] - ankle['y'])**2 +
90
+ (neck['z'] - ankle['z'])**2)**0.5
91
+
92
+ self.get_logger().info(
93
+ f'Person {person_id} - Height: {height:.2f}m'
94
+ )
95
+
96
+ # Example 2: Calculate shoulder width
97
+ if 'right_shoulder' in keypoints and 'left_shoulder' in keypoints:
98
+ rs = keypoints['right_shoulder']
99
+ ls = keypoints['left_shoulder']
100
+
101
+ shoulder_width = ((rs['x'] - ls['x'])**2 +
102
+ (rs['y'] - ls['y'])**2 +
103
+ (rs['z'] - ls['z'])**2)**0.5
104
+
105
+ self.get_logger().info(
106
+ f'Person {person_id} - Shoulder width: {shoulder_width:.2f}m'
107
+ )
108
+
109
+ # Example 3: Detect raised hands
110
+ if all(k in keypoints for k in ['neck', 'right_hand', 'left_hand']):
111
+ neck_z = keypoints['neck']['z']
112
+ right_hand_z = keypoints['right_hand']['z']
113
+ left_hand_z = keypoints['left_hand']['z']
114
+
115
+ if right_hand_z > neck_z + 0.2:
116
+ self.get_logger().info(f'Person {person_id} - Right hand raised!')
117
+ if left_hand_z > neck_z + 0.2:
118
+ self.get_logger().info(f'Person {person_id} - Left hand raised!')
119
+
120
+ except Exception as e:
121
+ self.get_logger().error(f'Error processing keypoints: {e}')
122
+
123
+
124
+ def main_simple(args=None):
125
+ """Run the simple keypoint subscriber example"""
126
+ rclpy.init(args=args)
127
+ node = KeypointSubscriberExample()
128
+
129
+ try:
130
+ rclpy.spin(node)
131
+ except KeyboardInterrupt:
132
+ pass
133
+ finally:
134
+ node.destroy_node()
135
+ rclpy.shutdown()
136
+
137
+
138
+ def main_processor(args=None):
139
+ """Run the keypoint processor example"""
140
+ rclpy.init(args=args)
141
+ node = KeypointProcessor()
142
+
143
+ try:
144
+ rclpy.spin(node)
145
+ except KeyboardInterrupt:
146
+ pass
147
+ finally:
148
+ node.destroy_node()
149
+ rclpy.shutdown()
150
+
151
+
152
+ def main(args=None):
153
+ """Main entry point - runs the simple subscriber by default"""
154
+ main_simple(args)
155
+
156
+
157
+ if __name__ == '__main__':
158
+ main()