This commit is contained in:
havoc420ubuntu 2025-08-17 14:45:25 +00:00
parent 7629321b52
commit 64fd701585
4 changed files with 151 additions and 2 deletions

View File

@ -39,10 +39,10 @@ def main():
Ctrl.base_msg.stop()
# GO STRAIGHT TEST
go_straight(Ctrl, msg, distance=0.2, absolute=True)
go_straight(Ctrl, msg, distance=0.2)
# TURN TEST
turn_degree_v2(Ctrl, msg, degree=90, absolute=True)
turn_degree_v2(Ctrl, msg, degree=90)
except KeyboardInterrupt:

View File

@ -0,0 +1,8 @@
图像信息记录 - 20250817_144238
图像尺寸: 1920 x 1080
编码格式: rgb8
步长: 5760
数据大小: 6220800 字节
ROS节点: simple_image_subscriber
话题: /rgb_camera/image_raw
图像数据已成功接收ROS模块工作正常!

32
requirements_clean.txt Normal file
View File

@ -0,0 +1,32 @@
# 机器狗控制系统 - 精简依赖列表
# 基于代码分析自动生成
# 核心计算库
numpy>=1.19.0
opencv-python>=4.5.0
# 通信和ROS2相关
rclpy>=2.0.0
sensor-msgs>=4.0.0
cv-bridge>=3.1.0
lcm>=1.4.0
# 计算机视觉和QR码识别
qreader>=3.0.0
# 机器学习
scikit-learn>=1.0.0
# 数据可视化
matplotlib>=3.3.0
# 配置文件处理
toml>=0.10.0
# 并行处理
joblib>=1.0.0
# 注意:
# 1. cyberdog_marker 是自定义ROS2包需要单独安装
# 2. 此列表基于代码分析生成,可能需要根据实际环境调整版本号
# 3. 部分ROS2相关包可能已通过ros-galactic-desktop等包安装

View File

@ -0,0 +1,109 @@
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from rclpy.qos import QoSProfile, QoSReliabilityPolicy, QoSHistoryPolicy
from datetime import datetime
import os
class SimpleImageSubscriber(Node):
def __init__(self):
super().__init__('simple_image_subscriber')
# Define QoS Profile
qos_profile = QoSProfile(
reliability=QoSReliabilityPolicy.BEST_EFFORT,
history=QoSHistoryPolicy.KEEP_LAST,
depth=10
)
self.subscription = self.create_subscription(
Image,
'/rgb_camera/image_raw',
self.image_callback,
qos_profile=qos_profile
)
self.subscription # Prevent unused variable warning
self.image_received = False # Flag to track if image is received
self.image_count = 0 # Count received images
def image_callback(self, msg):
if self.image_received:
return # Skip processing if already processed
try:
# Get image metadata
height = msg.height
width = msg.width
encoding = msg.encoding
step = msg.step
data_size = len(msg.data)
# Log image information
self.get_logger().info(f"收到图像消息!")
self.get_logger().info(f"图像尺寸: {width} x {height}")
self.get_logger().info(f"编码格式: {encoding}")
self.get_logger().info(f"步长: {step}")
self.get_logger().info(f"数据大小: {data_size} 字节")
# Save image data to a simple text file for verification
self.save_image_info(height, width, encoding, step, data_size)
self.image_received = True
self.image_count += 1
# Log success and continue listening for more images
self.get_logger().info(f"成功处理图像 #{self.image_count}")
# Optionally shutdown after receiving a few images
if self.image_count >= 3:
self.get_logger().info("已收到3张图像测试完成!")
self.destroy_node()
rclpy.shutdown()
exit(0)
except Exception as e:
self.get_logger().error(f'处理图像时出错: {str(e)}')
def save_image_info(self, height, width, encoding, step, data_size):
# Create output directory if it doesn't exist
output_dir = "./captured_images/dual_path"
os.makedirs(output_dir, exist_ok=True)
# Generate a timestamped filename
timestamp = datetime.now().strftime("%Y%m%d_%H%M%S")
filename = f"{output_dir}/image_info_{timestamp}.txt"
try:
with open(filename, 'w', encoding='utf-8') as f:
f.write(f"图像信息记录 - {timestamp}\n")
f.write(f"图像尺寸: {width} x {height}\n")
f.write(f"编码格式: {encoding}\n")
f.write(f"步长: {step}\n")
f.write(f"数据大小: {data_size} 字节\n")
f.write(f"ROS节点: {self.get_name()}\n")
f.write(f"话题: /rgb_camera/image_raw\n")
f.write("图像数据已成功接收ROS模块工作正常!\n")
self.get_logger().info(f"图像信息已保存到: {filename}")
except Exception as e:
self.get_logger().error(f"保存图像信息时出错: {str(e)}")
def main(args=None):
rclpy.init(args=args)
simple_subscriber = SimpleImageSubscriber()
print("启动简化的ROS图像订阅测试...")
print("正在监听话题: /rgb_camera/image_raw")
print("按 Ctrl+C 停止测试")
try:
rclpy.spin(simple_subscriber)
except KeyboardInterrupt:
print("\n测试被用户中断")
finally:
print("测试完成,清理资源...")
simple_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()