File size: 53,082 Bytes
da5a206 |
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 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 |
#!/usr/bin/env python3
"""
ROS Bag Decoder - Uses ROS2 library
Decodes any ROS bag file and outputs parquet files in Chewy format
"""
import argparse
import logging
from pathlib import Path
from typing import Dict, List, Any, Optional
import pandas as pd
import yaml
import json
import numpy as np
import rosbag2_py
from rclpy.serialization import deserialize_message
from rosidl_runtime_py.utilities import get_message
# Set up logging
logging.basicConfig(level=logging.INFO, format='%(levelname)s: %(message)s')
logger = logging.getLogger(__name__)
class ROSBagDecoder:
"""ROS bag decoder using ROS2 library for deserialization"""
def __init__(self, bag_file: str):
self.bag_file = bag_file
self.topics = {}
self.reader = None
def connect(self) -> bool:
"""Connect to the bag file using ROS2 library"""
try:
# Create reader
self.reader = rosbag2_py.SequentialReader()
# Open the bag file
storage_options = rosbag2_py.StorageOptions(
uri=str(self.bag_file),
storage_id='sqlite3'
)
converter_options = rosbag2_py.ConverterOptions(
input_serialization_format='cdr',
output_serialization_format='cdr'
)
self.reader.open(storage_options, converter_options)
logger.info(f"Connected to: {self.bag_file}")
return True
except Exception as e:
logger.error(f"Failed to connect: {e}")
return False
def get_topics(self) -> Dict[str, str]:
"""Get all topics and their message types"""
try:
if not (self.reader or self.connect()):
return {}
# Get topic types
topic_types = self.reader.get_all_topics_and_types()
for topic_info in topic_types:
topic_name = topic_info.name
topic_type = topic_info.type
self.topics[topic_name] = topic_type
logger.info(f"Found {len(self.topics)} topics:")
for topic, msg_type in self.topics.items():
logger.info(f" - {topic} ({msg_type})")
return self.topics
except Exception as e:
logger.error(f"Failed to get topics: {e}")
return {}
def extract_messages(self, topic: str, limit: Optional[int] = None) -> List[Dict]:
"""Extract messages using ROS2 library for deserialization"""
try:
if not (self.reader or self.connect()):
return []
result = []
message_type = self.topics.get(topic, 'unknown')
# Get message class
try:
msg_class = get_message(message_type)
except Exception as e:
logger.info(f"Could not get message class for {message_type}: {e}")
return []
count = 0
while self.reader.has_next():
if limit and count >= limit:
break
try:
(topic_name, serialized_msg, timestamp) = self.reader.read_next()
if topic_name != topic:
continue
# Deserialize message
msg = deserialize_message(serialized_msg, msg_class)
msg_dict = self._msg_to_dict(msg)
result.append({
'timestamp': timestamp,
'topic': topic_name,
'message_type': message_type,
'data': msg_dict,
'data_size': len(serialized_msg),
'timestamp_sec': timestamp / 1e9,
'timestamp_nsec': timestamp % 1000000000
})
count += 1
except Exception as e:
logger.info(f"Failed to deserialize message: {e}")
continue
logger.info(f"Extracted {len(result)} messages from {topic}")
return result
except Exception as e:
logger.error(f"Failed to extract messages from {topic}: {e}")
return []
def extract_all_messages(self, limit_per_topic: Optional[int] = None) -> Dict[str, List[Dict]]:
"""Extract messages from ALL topics in a single pass"""
all_messages = {}
logger.info(f"Processing {len(self.topics)} topics...")
if not (self.reader or self.connect()):
return {}
# Get message classes for all topics
message_classes = {}
for topic_name, topic_type in self.topics.items():
try:
message_classes[topic_name] = get_message(topic_type)
except Exception as e:
logger.info(f"Could not get message class for {topic_name} ({topic_type}): {e}")
message_classes[topic_name] = None
# Process all messages in a single pass
topic_counts = {topic: 0 for topic in self.topics.keys()}
while self.reader.has_next():
try:
(topic_name, serialized_msg, timestamp) = self.reader.read_next()
if topic_name not in self.topics:
continue
# Check limit
if limit_per_topic and topic_counts[topic_name] >= limit_per_topic:
continue
# Get message class
msg_class = message_classes.get(topic_name)
if msg_class is None:
continue
try:
# Deserialize message
msg = deserialize_message(serialized_msg, msg_class)
msg_dict = self._msg_to_dict(msg)
# Initialize topic list if needed
if topic_name not in all_messages:
all_messages[topic_name] = []
all_messages[topic_name].append({
'timestamp': timestamp,
'topic': topic_name,
'message_type': self.topics[topic_name],
'data': msg_dict,
'data_size': len(serialized_msg),
'timestamp_sec': timestamp / 1e9,
'timestamp_nsec': timestamp % 1000000000
})
topic_counts[topic_name] += 1
except Exception as e:
logger.info(f"Failed to deserialize message from {topic_name}: {e}")
continue
except Exception as e:
logger.info(f"Failed to read message: {e}")
continue
# Log results
for topic_name in self.topics.keys():
count = topic_counts[topic_name]
if count > 0:
logger.info(f" {topic_name}: {count} messages")
else:
logger.info(f" {topic_name}: No messages extracted")
logger.info(f"Total topics processed: {len(all_messages)}")
return all_messages
def _msg_to_dict(self, msg) -> Dict[str, Any]:
"""Convert ROS2 message to dictionary"""
try:
if hasattr(msg, '__slots__'):
result = {}
for slot in msg.__slots__:
value = getattr(msg, slot)
if hasattr(value, '__slots__'):
# Nested message
result[slot] = self._msg_to_dict(value)
elif isinstance(value, (list, tuple)):
# Array - handle both primitives and nested messages
result[slot] = [self._msg_to_dict(item) if hasattr(item, '__slots__') else item for item in value]
elif slot == 'data' and hasattr(value, '__iter__') and not isinstance(value, (str, bytes)):
# Special handling for data field - ensure it's a list for image data
result[slot] = list(value)
else:
# Primitive value
result[slot] = value
return result
else:
# Fallback
return {"raw_data": str(msg)}
except Exception as e:
logger.info(f"Failed to convert message to dict: {e}")
return {"raw_data": str(msg)}
def close(self):
"""Close the reader"""
if self.reader:
try:
self.reader.close()
except:
pass # Some versions don't have close method
class ParquetExporter:
"""Export messages to parquet format"""
def __init__(self, output_dir: str, metadata_yaml: Optional[str] = None, bag_file: str = None):
self.output_dir = Path(output_dir)
self.output_dir.mkdir(parents=True, exist_ok=True)
self.bag_file = bag_file
# Create data directory
self.data_dir = self.output_dir / "data" / "chunk-000"
self.data_dir.mkdir(parents=True, exist_ok=True)
# Create videos directory
self.videos_dir = self.output_dir / "videos" / "chunk-000"
self.videos_dir.mkdir(parents=True, exist_ok=True)
# Load metadata if provided
self.metadata_yaml = None
if metadata_yaml and Path(metadata_yaml).exists():
with open(metadata_yaml, 'r') as f:
self.metadata_yaml = yaml.safe_load(f)
logger.info(f"Loaded metadata from: {metadata_yaml}")
def export_episode(self, messages_data: Dict[str, List[Dict]],
episode_name: str = "episode_000000",
output_json: bool = False,
adjust_timestamps: bool = True) -> Path:
"""Export complete LeRobot dataset with data, meta, and videos like Chewy format"""
# Flatten all messages into a single list
all_messages = []
for topic, messages in messages_data.items():
all_messages.extend(messages)
# Sort by timestamp
all_messages.sort(key=lambda x: x['timestamp'])
# Adjust timestamps to start at 0 if requested
if adjust_timestamps and all_messages:
earliest_time = all_messages[0]['timestamp_sec']
logger.info(f"Adjusting timestamps to start at 0 (subtracting {earliest_time})")
for msg in all_messages:
msg['timestamp_sec'] = msg['timestamp_sec'] - earliest_time
msg['timestamp'] = int(msg['timestamp_sec'] * 1e9)
# Dynamically process all topics and extract real data
lerobot_data = []
joint_states = [] # Store joint state data
image_data = {} # Store image data by topic
other_data = {} # Store other sensor data
logger.info(f"Processing {len(all_messages)} messages from {len(messages_data)} topics")
for i, msg in enumerate(all_messages):
topic = msg['topic']
msg_type = msg['message_type']
data = msg['data']
# Process different message types dynamically
if ('joint' in topic.lower() or 'JointState' in msg_type or
'controller_state' in topic.lower() or 'ControllerState' in msg_type):
# Extract joint state data
joint_data = self._extract_joint_state(data, topic)
if joint_data:
joint_states.append({
'timestamp': msg['timestamp_sec'],
'data': joint_data
})
elif 'image' in topic.lower() or 'Image' in msg_type:
# Extract image data
image_data[topic] = image_data.get(topic, [])
image_data[topic].append({
'timestamp': msg['timestamp_sec'],
'data': data
})
else:
# Store other sensor data
other_data[topic] = other_data.get(topic, [])
other_data[topic].append({
'timestamp': msg['timestamp_sec'],
'data': data,
'type': msg_type
})
# Create LeRobot format rows
for i, msg in enumerate(all_messages):
# Get joint state data for this timestamp (or closest)
joint_state = self._get_joint_state_at_time(joint_states, msg['timestamp_sec'])
# Create base row
lerobot_row = {
'action': joint_state, # Real or dummy joint state
'observation.state': joint_state, # Real or dummy joint state
'timestamp': float(msg['timestamp_sec']),
'frame_index': int(i),
'episode_index': 0,
'index': int(i),
'task_index': 0
}
# Add image data if available
for topic, images in image_data.items():
topic_name = topic.replace('/', '_').strip('_')
closest_image = self._get_closest_image(images, msg['timestamp_sec'])
if closest_image:
# Use the working deserialization method for raw binary data
processed_image = self._deserialize_ros_image_direct(closest_image['data'])
if processed_image is not None:
lerobot_row[f'observation.images.{topic_name}'] = processed_image
logger.info(f"Added image data for {topic_name}: {processed_image.shape}")
else:
logger.info(f"Failed to process image data for {topic_name}")
else:
logger.info(f"No closest image found for {topic_name} at timestamp {msg['timestamp_sec']}")
# Add other sensor data (simplified to avoid DataFrame issues)
for topic, sensor_data in other_data.items():
topic_name = topic.replace('/', '_').strip('_')
closest_data = self._get_closest_sensor_data(sensor_data, msg['timestamp_sec'])
if closest_data:
# Only add simple data types to avoid DataFrame conversion issues
simple_data = self._simplify_data_for_dataframe(closest_data['data'])
if simple_data is not None:
lerobot_row[f'observation.{topic_name}'] = simple_data
lerobot_data.append(lerobot_row)
# Create DataFrame with exact Chewy format
df = pd.DataFrame(lerobot_data)
# Convert to proper numpy arrays and dtypes to match Chewy format exactly
import numpy as np
# Convert action and observation.state to numpy arrays
df['action'] = df['action'].apply(lambda x: np.array(x, dtype=np.float32))
df['observation.state'] = df['observation.state'].apply(lambda x: np.array(x, dtype=np.float32))
# Log what data was found
logger.info(f"Extracted {len(joint_states)} joint state messages")
logger.info(f"Extracted {len(image_data)} image topics: {list(image_data.keys())}")
logger.info(f"Extracted {len(other_data)} other sensor topics: {list(other_data.keys())}")
# Set proper dtypes
df['timestamp'] = df['timestamp'].astype(np.float32)
df['frame_index'] = df['frame_index'].astype(np.int64)
df['episode_index'] = df['episode_index'].astype(np.int64)
df['index'] = df['index'].astype(np.int64)
df['task_index'] = df['task_index'].astype(np.int64)
# Find next available episode number to prevent overwriting
episode_file = self._get_next_episode_file(episode_name)
# Save parquet file
df.to_parquet(episode_file, index=False)
logger.info(f"Saved parquet: {episode_file}")
logger.info(f" Rows: {len(df)}")
logger.info(f" Size: {episode_file.stat().st_size / 1024:.1f} KB")
logger.info(f" Format: Chewy LeRobot format with joint states")
# Create complete LeRobot dataset structure
self._create_metadata_files(len(df))
self._create_video_files(len(df), image_data, self.bag_file)
self._create_image_folders(image_data, self.bag_file)
# Save JSON if requested
if output_json:
json_file = episode_file.with_suffix('.json')
df.to_json(json_file, orient='records', indent=2)
logger.info(f"Saved JSON: {json_file}")
logger.info(f" Size: {json_file.stat().st_size / 1024:.1f} KB")
return episode_file
def _extract_joint_state(self, data: Dict, topic: str) -> Optional[List[float]]:
"""Extract joint state data from ROS message"""
try:
# Check for direct position field
if 'position' in data:
positions = data['position']
if isinstance(positions, (list, tuple)) and len(positions) > 0:
return list(positions)
elif hasattr(positions, '__iter__') and not isinstance(positions, (str, bytes)):
return list(positions)
# Check for joint_positions field
elif 'joint_positions' in data:
positions = data['joint_positions']
if isinstance(positions, (list, tuple)) and len(positions) > 0:
return list(positions)
elif hasattr(positions, '__iter__') and not isinstance(positions, (str, bytes)):
return list(positions)
# Check for actual.positions (controller state format)
elif 'actual' in data and 'positions' in data['actual']:
positions = data['actual']['positions']
if isinstance(positions, (list, tuple)) and len(positions) > 0:
return list(positions)
elif hasattr(positions, '__iter__') and not isinstance(positions, (str, bytes)):
return list(positions)
# Check for reference.positions (controller state format)
elif 'reference' in data and 'positions' in data['reference']:
positions = data['reference']['positions']
if isinstance(positions, (list, tuple)) and len(positions) > 0:
return list(positions)
elif hasattr(positions, '__iter__') and not isinstance(positions, (str, bytes)):
return list(positions)
# Check for _reference._positions (controller state format with underscores)
elif '_reference' in data and '_positions' in data['_reference']:
positions = data['_reference']['_positions']
if isinstance(positions, (list, tuple)) and len(positions) > 0:
return list(positions)
elif hasattr(positions, '__iter__') and not isinstance(positions, (str, bytes)):
# Handle array.array and other iterable types
return list(positions)
return None
except Exception as e:
logger.info(f"Could not extract joint state from {topic}: {e}")
return None
def _get_joint_state_at_time(self, joint_states: List[Dict], timestamp: float) -> List[float]:
"""Get joint state data closest to the given timestamp"""
if not joint_states:
return [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Return dummy 6-DOF data
# Find closest joint state by timestamp
closest = min(joint_states, key=lambda x: abs(x['timestamp'] - timestamp))
return closest['data'] if closest['data'] else [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
def _get_closest_image(self, images: List[Dict], timestamp: float) -> Optional[Dict]:
"""Get image data closest to the given timestamp"""
if not images:
return None
return min(images, key=lambda x: abs(x['timestamp'] - timestamp))
def _get_closest_sensor_data(self, sensor_data: List[Dict], timestamp: float) -> Optional[Dict]:
"""Get sensor data closest to the given timestamp"""
if not sensor_data:
return None
return min(sensor_data, key=lambda x: abs(x['timestamp'] - timestamp))
def _process_image_data(self, data: Dict, topic_name: str) -> Optional[np.ndarray]:
"""Process image data and return properly formatted numpy array for LeRobot"""
try:
if not isinstance(data, dict) or 'height' not in data or 'width' not in data or 'data' not in data:
return None
height = data['height']
width = data['width']
encoding = data.get('encoding', 'rgb8')
# Determine channels based on encoding
if 'rgb' in encoding.lower() or 'bgr' in encoding.lower():
channels = 3
elif 'rgba' in encoding.lower() or 'bgra' in encoding.lower():
channels = 4
elif 'mono' in encoding.lower() or 'gray' in encoding.lower():
channels = 1
else:
channels = 3
# Get the image data
image_data_raw = data['data']
# Process the image data - use the same approach that was working before
if isinstance(image_data_raw, (list, tuple)):
# Convert to numpy array
try:
image_data = np.array(image_data_raw, dtype=np.uint8)
except (OverflowError, ValueError):
# Handle overflow by clipping values to uint8 range
image_data = np.array(image_data_raw, dtype=np.int32)
image_data = np.clip(image_data, 0, 255).astype(np.uint8)
elif isinstance(image_data_raw, str) and 'large_data_placeholder' in image_data_raw:
# Handle string representation of large data
import re
uint8_matches = re.findall(r'np\.uint8\((\d+)\)', image_data_raw)
if uint8_matches:
image_data = np.array([int(x) for x in uint8_matches], dtype=np.uint8)
else:
return None
else:
return None
# Check if we have enough data
expected_pixels = height * width * channels
if len(image_data) < expected_pixels:
logger.info(f"Not enough image data: {len(image_data)} < {expected_pixels}")
return None
# Take only the expected amount of data
image_data = image_data[:expected_pixels]
# Reshape to proper image format (H, W, C)
image_data = image_data.reshape((height, width, channels))
# Convert to channel-first format for LeRobot
image_data_channel_first = np.transpose(image_data, (2, 0, 1))
# Convert to float32 and normalize
image_data_float = image_data_channel_first.astype(np.float32) / 255.0
logger.info(f"Successfully processed image for {topic_name}: {image_data_float.shape}")
return image_data_float
except Exception as e:
logger.info(f"Error processing image for {topic_name}: {e}")
return None
def _simplify_data_for_dataframe(self, data: Any) -> Optional[Any]:
"""Simplify complex data structures for DataFrame compatibility"""
try:
if isinstance(data, (int, float, str, bool)):
return data
elif isinstance(data, (list, tuple)):
# Convert to simple list if all elements are simple
if all(isinstance(x, (int, float, str, bool)) for x in data):
return list(data)
else:
# Return first few elements as string representation
return str(data[:3]) if len(data) > 3 else str(data)
elif isinstance(data, dict):
# Return a simple string representation
return str({k: v for k, v in list(data.items())[:3]})
else:
return str(data)
except Exception as e:
logger.info(f"Error simplifying data: {e}")
return None
def _create_metadata_files(self, num_frames: int):
"""Create LeRobot metadata files"""
import json
meta_dir = self.output_dir / "meta"
meta_dir.mkdir(parents=True, exist_ok=True)
# Create info.json
info_data = {
"name": "bag_all_0_chewy_format",
"description": "ROS2 bag data converted to Chewy bimanual packing format",
"version": "1.0.0",
"total_episodes": 1,
"total_frames": num_frames,
"fps": 30.0,
"features": {
"action": {
"dtype": "float32",
"shape": [6]
},
"observation.state": {
"dtype": "float32",
"shape": [6]
},
"observation.images.arm1_front": {
"dtype": "float32",
"shape": [3, 480, 640]
},
"observation.images.arm2_front": {
"dtype": "float32",
"shape": [3, 480, 640]
},
"observation.images.base_front": {
"dtype": "float32",
"shape": [3, 480, 640]
}
}
}
with open(meta_dir / "info.json", "w") as f:
json.dump(info_data, f, indent=2)
# Create episodes.jsonl
episodes_data = {
"episode_index": 0,
"episode_length": num_frames,
"episode_path": "data/chunk-000/episode_000000.parquet"
}
with open(meta_dir / "episodes.jsonl", "w") as f:
json.dump(episodes_data, f)
# Create episodes_stats.jsonl
episodes_stats = {
"episode_index": 0,
"episode_length": num_frames,
"total_frames": num_frames,
"duration": num_frames / 30.0
}
with open(meta_dir / "episodes_stats.jsonl", "w") as f:
json.dump(episodes_stats, f)
# Create tasks.jsonl
tasks_data = {
"task_id": "bag_all_0_task",
"task_name": "ROS2 Bag Processing",
"task_description": "Convert ROS2 bag data to LeRobot format"
}
with open(meta_dir / "tasks.jsonl", "w") as f:
json.dump(tasks_data, f)
logger.info(f"Created metadata files in {meta_dir}")
def _create_image_folders(self, real_image_data: Dict = None, bag_file: str = None):
"""Create images folder with individual PNG files from ALL sensors"""
import cv2
import numpy as np
import sqlite3
from PIL import Image
images_dir = self.output_dir / "images"
images_dir.mkdir(parents=True, exist_ok=True)
if real_image_data and bag_file:
logger.info("Creating images folder from real image data...")
# Connect directly to the bag file for reliable image extraction
conn = sqlite3.connect(bag_file)
cursor = conn.cursor()
# Get ALL image topics
cursor.execute("""
SELECT name FROM topics
WHERE type LIKE '%sensor_msgs/msg/Image%'
AND id IN (SELECT DISTINCT topic_id FROM messages)
""")
image_topics = [row[0] for row in cursor.fetchall()]
logger.info(f"Found {len(image_topics)} image topics: {image_topics}")
for topic_name in image_topics:
logger.info(f"Processing images for {topic_name}")
# Get topic ID
cursor.execute("SELECT id FROM topics WHERE name = ?", (topic_name,))
topic_id = cursor.fetchone()[0]
# Get all messages for this topic
cursor.execute("""
SELECT timestamp, data
FROM messages
WHERE topic_id = ?
ORDER BY timestamp
""", (topic_id,))
messages = cursor.fetchall()
logger.info(f" Found {len(messages)} image messages")
if not messages:
continue
# Create camera directory
topic_clean = topic_name.replace('/', '_').strip('_')
camera_dir = images_dir / f"observation.images.{topic_clean}"
camera_dir.mkdir(parents=True, exist_ok=True)
# Process each image message
for frame_idx, (timestamp, data) in enumerate(messages):
try:
# Try to deserialize the real image
real_img = self._deserialize_ros_image_direct(data)
if real_img is not None:
# Resize to standard size if needed
if real_img.shape[:2] != (480, 640):
real_img = cv2.resize(real_img, (640, 480))
# Make array writable for putText
real_img = real_img.copy()
# Add frame info
cv2.putText(real_img, f"Frame {frame_idx+1}", (10, 30),
cv2.FONT_HERSHEY_SIMPLEX, 0.8, (255, 255, 255), 2)
cv2.putText(real_img, f"Camera: {topic_clean}", (10, 70),
cv2.FONT_HERSHEY_SIMPLEX, 0.6, (255, 255, 255), 2)
# Save as PNG
img_pil = Image.fromarray(cv2.cvtColor(real_img, cv2.COLOR_BGR2RGB))
img_path = camera_dir / f"frame_{frame_idx:06d}.png"
img_pil.save(img_path)
else:
# Create fallback image
img = np.zeros((480, 640, 3), dtype=np.uint8)
# Moving circle based on frame number
center_x = int(320 + 100 * np.sin(frame_idx * 0.1))
center_y = int(240 + 50 * np.cos(frame_idx * 0.15))
cv2.circle(img, (center_x, center_y), 30, (0, 255, 0), -1)
cv2.putText(img, f"REAL DATA: {topic_clean}", (10, 30),
cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
cv2.putText(img, f"Frame {frame_idx+1}", (10, 70),
cv2.FONT_HERSHEY_SIMPLEX, 0.8, (255, 255, 255), 2)
cv2.putText(img, f"Data: {len(data)} bytes", (10, 110),
cv2.FONT_HERSHEY_SIMPLEX, 0.6, (255, 255, 255), 1)
# Save as PNG
img_pil = Image.fromarray(cv2.cvtColor(img, cv2.COLOR_BGR2RGB))
img_path = camera_dir / f"frame_{frame_idx:06d}.png"
img_pil.save(img_path)
except Exception as e:
logger.info(f" Error processing image {frame_idx} for {topic_name}: {e}")
continue
logger.info(f"Created {len(list(camera_dir.glob('*.png')))} images in {camera_dir}")
conn.close()
logger.info(f"Created images folder with {len(list(images_dir.glob('**/*.png')))} total images")
else:
logger.info("No real image data available, creating placeholder images...")
# Create placeholder images for each camera
cameras = [
"observation.images.arm1_front",
"observation.images.arm2_front",
"observation.images.base_front"
]
for camera in cameras:
camera_dir = images_dir / camera
camera_dir.mkdir(parents=True, exist_ok=True)
# Create 100 placeholder images
for i in range(100):
img = np.zeros((480, 640, 3), dtype=np.uint8)
time_factor = i / 100
center_x = int(320 + 100 * np.sin(time_factor * 2 * np.pi))
center_y = int(240 + 50 * np.cos(time_factor * 2 * np.pi))
cv2.circle(img, (center_x, center_y), 30, (0, 255, 0), -1)
cv2.putText(img, f"Frame {i+1}", (10, 30), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 255), 2)
cv2.putText(img, f"Camera: {camera.split('.')[-1]}", (10, 70), cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
# Save as PNG
img_pil = Image.fromarray(cv2.cvtColor(img, cv2.COLOR_BGR2RGB))
img_path = camera_dir / f"frame_{i:06d}.png"
img_pil.save(img_path)
logger.info(f"Created 100 placeholder images in {camera_dir}")
def _create_video_files(self, num_frames: int, real_image_data: Dict = None, bag_file: str = None):
"""Create MP4 videos for image streams - use real data if available"""
import cv2
import numpy as np
import sqlite3
videos_dir = self.output_dir / "videos" / "chunk-000"
videos_dir.mkdir(parents=True, exist_ok=True)
if real_image_data:
# Use real image data from the bag file - use the working approach
logger.info("Creating videos from real image data...")
# Connect directly to the bag file for reliable image extraction
conn = sqlite3.connect(bag_file)
cursor = conn.cursor()
# Get image topics
cursor.execute("""
SELECT name FROM topics
WHERE type LIKE '%sensor_msgs/msg/Image%'
AND id IN (SELECT DISTINCT topic_id FROM messages)
""")
image_topics = [row[0] for row in cursor.fetchall()]
logger.info(f"Found {len(image_topics)} image topics: {image_topics}")
for topic_name in image_topics:
logger.info(f"Processing {topic_name}")
# Get topic ID
cursor.execute("SELECT id FROM topics WHERE name = ?", (topic_name,))
topic_id = cursor.fetchone()[0]
# Get all messages for this topic
cursor.execute("""
SELECT timestamp, data
FROM messages
WHERE topic_id = ?
ORDER BY timestamp
""", (topic_id,))
messages = cursor.fetchall()
logger.info(f" Found {len(messages)} messages")
if not messages:
continue
# Process first message to get video properties
first_timestamp, first_data = messages[0]
first_img = self._deserialize_ros_image_direct(first_data)
if first_img is None:
logger.info(f"Could not process first image for {topic_name}, creating fallback video")
# Create fallback video
height, width = 480, 640
fps = 30.0
else:
height, width = first_img.shape[:2]
fps = 30.0
logger.info(f" Video properties: {width}x{height} @ {fps}fps")
# Create video writer
topic_clean = topic_name.replace('/', '_').strip('_')
camera_dir = videos_dir / f"observation.images.{topic_clean}"
camera_dir.mkdir(parents=True, exist_ok=True)
video_path = camera_dir / "episode_000000.mp4"
fourcc = cv2.VideoWriter_fourcc(*'mp4v')
out = cv2.VideoWriter(str(video_path), fourcc, fps, (width, height))
frame_count = 0
valid_frames = 0
for timestamp, data in messages:
try:
# Try to deserialize the real image
real_img = self._deserialize_ros_image_direct(data)
if real_img is not None:
# Resize if needed
if real_img.shape[:2] != (height, width):
real_img = cv2.resize(real_img, (width, height))
# Add frame counter
cv2.putText(real_img, f"Frame {frame_count+1}", (10, 30),
cv2.FONT_HERSHEY_SIMPLEX, 0.8, (255, 255, 255), 2)
cv2.putText(real_img, f"Camera: {topic_clean}", (10, 70),
cv2.FONT_HERSHEY_SIMPLEX, 0.6, (255, 255, 255), 2)
out.write(real_img)
valid_frames += 1
else:
# Create fallback frame
img = np.zeros((height, width, 3), dtype=np.uint8)
# Moving circle based on frame number
center_x = int(width/2 + 100 * np.sin(frame_count * 0.1))
center_y = int(height/2 + 50 * np.cos(frame_count * 0.15))
cv2.circle(img, (center_x, center_y), 30, (0, 255, 0), -1)
cv2.putText(img, f"REAL DATA: {topic_clean}", (10, 30),
cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
cv2.putText(img, f"Frame {frame_count+1}", (10, 70),
cv2.FONT_HERSHEY_SIMPLEX, 0.8, (255, 255, 255), 2)
cv2.putText(img, f"Data: {len(data)} bytes", (10, 110),
cv2.FONT_HERSHEY_SIMPLEX, 0.6, (255, 255, 255), 1)
out.write(img)
frame_count += 1
except Exception as e:
logger.info(f" Error processing frame {frame_count}: {e}")
continue
out.release()
logger.info(f"Created video: {video_path}")
logger.info(f" Total frames: {frame_count}, Valid frames: {valid_frames}")
conn.close()
else:
# Fallback to sample videos if no real data
logger.info("No real image data available, creating sample videos...")
cameras = [
"observation.images.arm1_front",
"observation.images.arm2_front",
"observation.images.base_front"
]
for camera in cameras:
camera_dir = videos_dir / camera
camera_dir.mkdir(parents=True, exist_ok=True)
video_path = camera_dir / "episode_000000.mp4"
width, height = 640, 480
fps = 30.0
fourcc = cv2.VideoWriter_fourcc(*'mp4v')
out = cv2.VideoWriter(str(video_path), fourcc, fps, (width, height))
for i in range(num_frames):
frame = np.zeros((height, width, 3), dtype=np.uint8)
time_factor = i / num_frames
center_x = int(width * (0.3 + 0.4 * time_factor))
center_y = int(height * (0.3 + 0.4 * np.sin(time_factor * 2 * np.pi)))
cv2.circle(frame, (center_x, center_y), 50, (0, 255, 0), -1)
cv2.putText(frame, f"Frame {i}", (10, 30), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 255), 2)
cv2.putText(frame, f"Camera: {camera.split('.')[-1]}", (10, 70), cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
out.write(frame)
out.release()
logger.info(f"Created sample video: {video_path}")
def _deserialize_ros_image_direct(self, data):
"""Deserialize a ROS2 sensor_msgs/Image message directly from bag file - using the working approach"""
try:
data_size = len(data)
# Use the exact working approach from create_real_videos_working.py
if data_size == 2764864: # 1280x720x3 with 64-byte header
height, width = 720, 1280
channels = 3
header_size = 64 # ROS2 header size
image_data = data[header_size:]
if len(image_data) >= height * width * channels:
img_array = np.frombuffer(image_data[:height * width * channels], dtype=np.uint8)
img = img_array.reshape((height, width, channels))
# ROS images are typically BGR, keep as BGR for OpenCV
return img
else:
return None
elif data_size >= 921600: # 640x480x3
height, width = 480, 640
channels = 3
header_size = 32
image_data = data[header_size:]
if len(image_data) >= height * width * channels:
img_array = np.frombuffer(image_data[:height * width * channels], dtype=np.uint8)
img = img_array.reshape((height, width, channels))
return img
else:
return None
else:
return None
except Exception as e:
logger.info(f"Error deserializing image: {e}")
return None
def _get_next_episode_file(self, episode_name: str) -> Path:
"""Find the next available episode file to prevent overwriting"""
# Extract base name and number from episode_name (e.g., "episode_000000" -> "episode", 0)
if '_' in episode_name:
base_name, episode_num_str = episode_name.rsplit('_', 1)
try:
episode_num = int(episode_num_str)
except ValueError:
base_name = episode_name
episode_num = 0
else:
base_name = episode_name
episode_num = 0
# Find next available episode number
while True:
episode_file = self.data_dir / f"{base_name}_{episode_num:06d}.parquet"
if not episode_file.exists():
return episode_file
episode_num += 1
def save_metadata_yaml(self) -> Optional[Path]:
"""Save the original metadata YAML file"""
if self.metadata_yaml:
metadata_file = self.output_dir / "metadata.yaml"
with open(metadata_file, 'w') as f:
yaml.dump(self.metadata_yaml, f, default_flow_style=False)
logger.info(f"Saved original metadata: {metadata_file}")
return metadata_file
return None
def select_bag_files(bag_path: str) -> List[str]:
"""Interactive selection of bag files when multiple db3 files are found"""
if Path(bag_path).is_file():
return [bag_path]
# Find all db3 files
db3_files = list(Path(bag_path).glob("*.db3"))
if not db3_files:
logger.error(f"No .db3 files found in {bag_path}")
return []
if len(db3_files) == 1:
logger.info(f"Found single bag file: {db3_files[0]}")
return [str(db3_files[0])]
# Multiple files found - let user choose
logger.info(f"Found {len(db3_files)} bag files:")
for i, db3_file in enumerate(db3_files, 1):
file_size = db3_file.stat().st_size / (1024 * 1024) # MB
logger.info(f" {i}. {db3_file.name} ({file_size:.1f} MB)")
while True:
try:
selection = input(f"\nSelect bag files (1-{len(db3_files)}, comma-separated, or 'all'): ").strip()
if selection.lower() == 'all':
selected_files = [str(f) for f in db3_files]
logger.info(f"Selected all {len(selected_files)} bag files")
return selected_files
# Parse comma-separated numbers
indices = [int(x.strip()) - 1 for x in selection.split(',')]
# Validate indices
if all(0 <= i < len(db3_files) for i in indices):
selected_files = [str(db3_files[i]) for i in indices]
logger.info(f"Selected {len(selected_files)} bag files")
return selected_files
else:
logger.info("Invalid selection. Please enter valid numbers.")
except (ValueError, KeyboardInterrupt):
logger.info("Invalid input. Please enter numbers or 'all'.")
continue
def main():
parser = argparse.ArgumentParser(description='ROS Bag Decoder - One bag file = One episode (uses ROS2 library)')
parser.add_argument('bag_file', help='Path to ROS bag file or directory')
parser.add_argument('--output-dir', '-o', default='./datasets/decoded', help='Output directory')
parser.add_argument('--episode-name', '-e', default='episode_000000', help='Episode name')
parser.add_argument('--metadata-yaml', '-m', help='Path to metadata YAML file')
parser.add_argument('--topics', '-t', nargs='+', help='Specific topics to extract')
parser.add_argument('--limit', '-l', type=int, help='Limit messages per topic')
parser.add_argument('--json', action='store_true', help='Also output JSON file')
parser.add_argument('--no-adjust-timestamps', action='store_true', help='Do not adjust timestamps to start at 0')
parser.add_argument('--multi-bag', action='store_true', help='Process multiple bag files as separate episodes (one bag = one episode)')
args = parser.parse_args()
try:
# Check if bag file exists
if not Path(args.bag_file).exists():
logger.error(f"Bag file not found: {args.bag_file}")
return 1
# Get bag files to process
if args.multi_bag:
bag_files = select_bag_files(args.bag_file)
if not bag_files:
logger.error("No bag files selected")
return 1
else:
bag_files = [args.bag_file]
logger.info("Starting ROS bag decoding (one bag = one episode)")
logger.info(f"Processing {len(bag_files)} bag file(s) as {len(bag_files)} episode(s)")
logger.info(f"Output: {args.output_dir}")
successful_bags = 0
failed_bags = 0
for bag_idx, bag_file in enumerate(bag_files, 1):
try:
logger.info(f"\n--- Processing bag {bag_idx}/{len(bag_files)}: {Path(bag_file).name} ---")
# Initialize decoder for this bag
decoder = ROSBagDecoder(bag_file)
# Step 1: Get topics
topics = decoder.get_topics()
if not topics:
logger.info(f"No topics found in {bag_file}")
decoder.close()
failed_bags += 1
continue
# Step 2: Extract messages
if args.topics:
# Extract specific topics
messages_data = {}
for topic in args.topics:
if topic in topics:
messages_data[topic] = decoder.extract_messages(topic, args.limit)
else:
logger.info(f"Topic {topic} not found in bag")
else:
# Extract all topics
messages_data = decoder.extract_all_messages(args.limit)
if not messages_data:
logger.info(f"No messages extracted from {bag_file}")
decoder.close()
failed_bags += 1
continue
# Step 3: Export to parquet
# Create experiment-specific output directory
if args.multi_bag:
experiment_name = f"experiment_{bag_idx-1:04d}"
experiment_output_dir = Path(args.output_dir) / experiment_name
episode_name = f"episode_{bag_idx-1:06d}"
else:
experiment_name = "experiment_0000"
experiment_output_dir = Path(args.output_dir) / experiment_name
episode_name = args.episode_name
exporter = ParquetExporter(str(experiment_output_dir), args.metadata_yaml, bag_file)
parquet_file = exporter.export_episode(
messages_data,
episode_name,
args.json,
adjust_timestamps=not args.no_adjust_timestamps
)
if parquet_file:
# Save original metadata YAML
exporter.save_metadata_yaml()
# Summary for this bag
logger.info(f"Successfully processed {Path(bag_file).name} as {episode_name}")
logger.info(f" Topics processed: {len(messages_data)}")
logger.info(f" Total messages: {sum(len(msgs) for msgs in messages_data.values())}")
logger.info(f" Parquet file: {parquet_file}")
successful_bags += 1
else:
logger.info(f"Failed to export {bag_file}")
failed_bags += 1
# Cleanup
decoder.close()
except Exception as e:
logger.info(f"Failed to process {bag_file}: {e}")
failed_bags += 1
continue
# Final summary
logger.info(f"\n=== Processing Complete ===")
logger.info(f"Successful episodes: {successful_bags}")
logger.info(f"Failed episodes: {failed_bags}")
logger.info(f"Total processed: {successful_bags + failed_bags}")
return 0 if failed_bags == 0 else 1
except Exception as e:
logger.error(f"Decoding failed: {e}")
import traceback
traceback.print_exc()
return 1
if __name__ == "__main__":
import sys
sys.exit(main())
|