Luis Yoichi Morales
commited on
Commit
·
87aa606
1
Parent(s):
81eb63b
publish keypoints, not only visual markers
Browse files
keypoint-db/ws/src/db_loader/db_loader/keypoint_publisher.py
CHANGED
|
@@ -4,6 +4,8 @@ import rclpy
|
|
| 4 |
from rclpy.node import Node
|
| 5 |
from visualization_msgs.msg import Marker, MarkerArray
|
| 6 |
from geometry_msgs.msg import Point
|
|
|
|
|
|
|
| 7 |
import pandas as pd
|
| 8 |
import numpy as np
|
| 9 |
import argparse
|
|
@@ -21,6 +23,14 @@ class KeypointPublisher(Node):
|
|
| 21 |
100
|
| 22 |
)
|
| 23 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 24 |
self.playback_speed = playback_speed
|
| 25 |
self.interpolate = interpolate
|
| 26 |
self.previous_persons = set()
|
|
@@ -110,7 +120,8 @@ class KeypointPublisher(Node):
|
|
| 110 |
self.update_rate = publish_rate
|
| 111 |
self.timer = self.create_timer(1.0 / self.update_rate, self.publish_callback)
|
| 112 |
self.get_logger().info(f'Starting playback at {playback_speed}x speed')
|
| 113 |
-
self.get_logger().info(f'Publishing
|
|
|
|
| 114 |
self.get_logger().info(f'Interpolation: {"ENABLED" if self.interpolate else "DISABLED"}')
|
| 115 |
|
| 116 |
def _generate_color(self):
|
|
@@ -316,6 +327,37 @@ class KeypointPublisher(Node):
|
|
| 316 |
|
| 317 |
return markers
|
| 318 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 319 |
def _init_multi_chunk_mode(self, index_file_path):
|
| 320 |
"""Initialize multi-chunk playback mode from index file"""
|
| 321 |
try:
|
|
@@ -538,6 +580,13 @@ class KeypointPublisher(Node):
|
|
| 538 |
publish_timestamp
|
| 539 |
)
|
| 540 |
marker_array.markers.extend(person_markers)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 541 |
|
| 542 |
mode_str = "interpolated" if self.interpolate else "nearest"
|
| 543 |
self.get_logger().debug(f'Created {mode_str} markers for {len(unique_persons)} persons at t={publish_timestamp:.2f}s')
|
|
|
|
| 4 |
from rclpy.node import Node
|
| 5 |
from visualization_msgs.msg import Marker, MarkerArray
|
| 6 |
from geometry_msgs.msg import Point
|
| 7 |
+
from std_msgs.msg import String
|
| 8 |
+
import json
|
| 9 |
import pandas as pd
|
| 10 |
import numpy as np
|
| 11 |
import argparse
|
|
|
|
| 23 |
100
|
| 24 |
)
|
| 25 |
|
| 26 |
+
# Publisher for keypoint data (JSON format via String message)
|
| 27 |
+
# Contains person_id, timestamp, and all keypoints with names and positions
|
| 28 |
+
self.keypoints_pub = self.create_publisher(
|
| 29 |
+
String,
|
| 30 |
+
'skeleton_keypoints',
|
| 31 |
+
100
|
| 32 |
+
)
|
| 33 |
+
|
| 34 |
self.playback_speed = playback_speed
|
| 35 |
self.interpolate = interpolate
|
| 36 |
self.previous_persons = set()
|
|
|
|
| 120 |
self.update_rate = publish_rate
|
| 121 |
self.timer = self.create_timer(1.0 / self.update_rate, self.publish_callback)
|
| 122 |
self.get_logger().info(f'Starting playback at {playback_speed}x speed')
|
| 123 |
+
self.get_logger().info(f'Publishing at {publish_rate} Hz')
|
| 124 |
+
self.get_logger().info(f'Topics: /skeleton_markers (visualization), /skeleton_keypoints (JSON data)')
|
| 125 |
self.get_logger().info(f'Interpolation: {"ENABLED" if self.interpolate else "DISABLED"}')
|
| 126 |
|
| 127 |
def _generate_color(self):
|
|
|
|
| 327 |
|
| 328 |
return markers
|
| 329 |
|
| 330 |
+
def _publish_keypoints_for_person(self, person_id, frame, publish_timestamp):
|
| 331 |
+
"""Publish keypoint positions and metadata for a single person as JSON"""
|
| 332 |
+
# Create metadata dictionary with all keypoint information
|
| 333 |
+
metadata = {
|
| 334 |
+
'person_id': str(person_id),
|
| 335 |
+
'timestamp': publish_timestamp,
|
| 336 |
+
'keypoints': []
|
| 337 |
+
}
|
| 338 |
+
|
| 339 |
+
# Extract all keypoint positions with their names
|
| 340 |
+
for keypoint_name in self.keypoint_names:
|
| 341 |
+
pos = self._get_keypoint_position(frame, keypoint_name)
|
| 342 |
+
|
| 343 |
+
if pos is not None:
|
| 344 |
+
metadata['keypoints'].append({
|
| 345 |
+
'name': keypoint_name,
|
| 346 |
+
'position': {
|
| 347 |
+
'x': float(pos[0]),
|
| 348 |
+
'y': float(pos[1]),
|
| 349 |
+
'z': float(pos[2])
|
| 350 |
+
}
|
| 351 |
+
})
|
| 352 |
+
|
| 353 |
+
# Publish as JSON string (only if we have at least one keypoint)
|
| 354 |
+
if metadata['keypoints']:
|
| 355 |
+
msg = String()
|
| 356 |
+
msg.data = json.dumps(metadata)
|
| 357 |
+
self.keypoints_pub.publish(msg)
|
| 358 |
+
|
| 359 |
+
|
| 360 |
+
|
| 361 |
def _init_multi_chunk_mode(self, index_file_path):
|
| 362 |
"""Initialize multi-chunk playback mode from index file"""
|
| 363 |
try:
|
|
|
|
| 580 |
publish_timestamp
|
| 581 |
)
|
| 582 |
marker_array.markers.extend(person_markers)
|
| 583 |
+
|
| 584 |
+
# Publish keypoint data for this person
|
| 585 |
+
self._publish_keypoints_for_person(
|
| 586 |
+
person_id_str,
|
| 587 |
+
frame,
|
| 588 |
+
publish_timestamp
|
| 589 |
+
)
|
| 590 |
|
| 591 |
mode_str = "interpolated" if self.interpolate else "nearest"
|
| 592 |
self.get_logger().debug(f'Created {mode_str} markers for {len(unique_persons)} persons at t={publish_timestamp:.2f}s')
|
keypoint-db/ws/src/db_loader/setup.py
CHANGED
|
@@ -35,6 +35,7 @@ setup(
|
|
| 35 |
'layout_visualizer = db_loader.layout_visualizer:main',
|
| 36 |
'keypoint_publisher = db_loader.keypoint_publisher:main',
|
| 37 |
'index_keypoint_publisher = db_loader.index_keypoint_publisher:main',
|
|
|
|
| 38 |
],
|
| 39 |
},
|
| 40 |
)
|
|
|
|
| 35 |
'layout_visualizer = db_loader.layout_visualizer:main',
|
| 36 |
'keypoint_publisher = db_loader.keypoint_publisher:main',
|
| 37 |
'index_keypoint_publisher = db_loader.index_keypoint_publisher:main',
|
| 38 |
+
'keypoint_subscriber = db_loader.keypoint_subscriber:main',
|
| 39 |
],
|
| 40 |
},
|
| 41 |
)
|