手撕低成本全收工DIY机器人3

摄像头接入接口

环境

硬件

  • 魔百盒CM311-1A-YST
  • 外置摄像头(USB接口)

软件

  • Armbian

工具

  • cheese
  • usb_cam
  • v4l-utils
  • image-view

步骤

  • 通过usb接入摄像头

  • 查看usb 摄像头设备

    • ls /dev/video*
    • v4l2-ctl --list-devices (apt install v4l-utils)
    • 获取摄像头信息 v4l2-ctl --list-formats-ext -d /dev/video2
      • 查看摄像头支持的pixel-format
ioctl: VIDIOC_ENUM_FMT
        Type: Video Capture

        [0]: 'YUYV' (YUYV 4:2:2)
  • 安装usb-cam相关库

    • apt-get install ros-iron-usb-cam
    • apt-get install ros-iron-image-view
    • apt-get install ros-iron-v4l2-camera
  • 发布主题
    ros2 run usb_cam usb_cam_node_exe --ros-args -p video_device:=“/dev/video2” -p image_size:=[640,480]

  • 验证

    • ros2 topic list
    • ros2 topic echo /image_raw --no-arr
    • ros2 run rqt_image_view rqt_image_view
  • 相机标定

    • ros2 run camera_calibration cameracalibrator --size 6x9 --square 0.025 --ros-args --remap /image:=/image_raw --ros-args --remap camera:=/default_cam
    • cameracalibrator.py标定程序需要以下几个输入参数。1)size:标定棋盘格的内部角点个数,这里使用的棋盘一共有6行,每行有8个内部角点。2)square:这个参数对应每个棋盘格的边长,单位是米。3)image和camera:设置摄像头发布的图像话题

    相机标定结果文件拷贝到相应目录

    • RVIZ2 验证

      • 添加Camera,配置参数
    • 结合openCV验证

import rclpy
from sensor_msgs.msg import Image, CameraInfo
from cv_bridge import CvBridge
import cv2

class ImageSubscriber:
    def __init__(self):
        self.bridge = CvBridge()
        self.image_subscription = None
        self.camera_info_subscription = None

        rclpy.init()
        self.node = rclpy.create_node('image_subscriber_node')

        # 修改为新的主题名称
        self.image_subscription = self.node.create_subscription(Image, '/image_raw', self.image_callback, 10)
        self.camera_info_subscription = self.node.create_subscription(CameraInfo, '/usb_cam/camera_info', self.camera_info_callback, 10)

    def image_callback(self, msg):
        try:
            print("Received image message");
            cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8")
            self.process_image(cv_image)
        except Exception as e:
            print(f"Error processing image: {e}")

    def process_image(self, cv_image):
        # 在这里可以添加对图像的处理逻辑
        # 例如显示图像
        print("Deal image message");

        # 假设 cv_image 是你要处理的图像
        # cv_image = cv2.imread('your_image_file.jpg')

        # 将图像转换为灰度图像
        gray = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)

        # 使用阈值操作来二值化图像
        _, thresholded = cv2.threshold(gray, 127, 255, cv2.THRESH_BINARY)

        # 使用 findContours 函数来提取轮廓
        contours, _ = cv2.findContours(thresholded, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)

        # 使用红色(在 OpenCV 中,颜色表示为 BGR,所以红色是 (0, 0, 255))绘制轮廓
        # 第三个参数是轮廓的索引,-1 表示绘制所有轮廓
        # 第四个参数是颜色
        # 第五个参数是线条的厚度
        cv2.drawContours(cv_image, contours, -1, (0, 0, 255), 3)

        # 显示图像
        cv2.imshow('Image with contours', cv_image)
        cv2.waitKey(0)
        cv2.destroyAllWindows()

    def camera_info_callback(self, msg):
        # 处理相机信息的回调函数
        # 这里可以添加处理相机信息的逻辑
        pass

    def spin(self):
        rclpy.spin(self.node)

    def destroy_node(self):
        if self.node:
            self.node.destroy_node()
            rclpy.shutdown()

if __name__ == '__main__':
    print("Creating ImageSubcriber")
    subscriber = ImageSubscriber()
    try:
        print("Starting spin")
        subscriber.spin()
    except KeyboardInterrupt:
        print("Shutting down...")
    finally:
        print("Stop node")
        subscriber.destroy_node()

至此摄像头集成完成。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

新说一二

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值