亚博microros小车-原生ubuntu支持系列:4-手部检测
一 准备工作
在学习手部检测之前,有2个准备工作。
1 确保小车的摄像头能显示画面
参见:亚博microros小车-原生ubuntu支持系列:2-摄像头控制-CSDN博客
启动图传代理:
docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:humble udp4 --port 9999 -v4
2 消息接口已引用
bohu@bohu-TM1701:~/yahboomcar/yahboomcar_ws$ ros2 interface show yahboomcar_msgs/msg/PointArray
geometry_msgs/Point[] pointsfloat64 xfloat64 yfloat64 z
二 背景知识
以下摘自亚博学习资料:
1、简介
MediaPipe是⼀款由Google开发并开源的数据流处理机器学习应⽤开发框架。它是⼀个基于图的数据处理管线,⽤于构建使⽤了多种形式的数据源,如视频、⾳频、传感器数据以及任何时间序列数据。MediaPipe是跨平台的,可以运⾏在嵌⼊式平台(树莓派等),移动设备(iOS和Android),⼯作站和服务器上,并⽀持移动端GPU加速。 MediaPipe为实时和流媒体提供跨平台、可定制的ML解决⽅案。MediaPipe 的核⼼框架由 C++ 实现,并提供 Java 以及 Objective C 等语⾔的⽀持。MediaPipe 的主要概念包括数据包(Packet)、数据流(Stream)、计算单元(Calculator)、图(Graph)以及⼦图(Subgraph)。
MediaPipe的特点:
- 端到端加速:内置的快速ML推理和处理即使在普通硬件上也能加速。
- ⼀次构建,随时随地部署:统⼀解决⽅案适⽤于Android、iOS、桌⾯/云、web和物联⽹。
- 即⽤解决⽅案:展⽰框架全部功能的尖端ML解决⽅案。
- 免费开源:Apache2.0下的框架和解决⽅案,完全可扩展和定制。
2、MediaPipe Hands
MediaPipe Hands是⼀款⾼保真的⼿和⼿指跟踪解决⽅案。它利⽤机器学习(ML)从⼀帧中推断出21个⼿的3D坐标。
在对整个图像进⾏⼿掌检测后,根据⼿部标记模型通过回归对检测到的⼿区域内的21个3D⼿关节坐标进⾏精确的关键点定位,即直接坐标预测。该模型学习⼀致的内部⼿姿势表⽰,甚⾄对部分可⻅的⼿和⾃我遮挡也具有鲁棒性。
为了获得地⾯真实数据,⽤了21个3D坐标⼿动注释了约30K幅真实世界的图像,如下所⽰(从图像深度图中获取Z值,如果每个对应坐标都有Z值)。为了更好地覆盖可能的⼿部姿势,并对⼿部⼏何体的性质提供额外的监督,还绘制了各种背景下的⾼质量合成⼿部模型,并将其映射到相应的3D坐标。
看完这个大概有个了解,并不直观,然后就是代码了,这种对于新人并不友好。我们在连接小车的摄像头之前,先跟网上的大佬体验下笔记本自带摄像头的手部识别 。
MediaPipe一些函数:来自:学习 MediaPipe 手部检测和手势识别(1)_mediapipe.solutions.hands-CSDN博客
hand初始化参数
static_image_mode:静态图片输入模式,默认值为 False。是否将输入图片视为一批不相关的静态图片。
max_num_hands:识别手掌的最大数目,默认值为 2。
model_complexity:模型复杂度,默认值为 1,取值 0/1。值越大,模型越复杂,识别越精确,耗时越久。
min_detection_confidence:最低检测置信度,默认值为 0.5,取值 0.0 ~ 1.0。值越大,对手掌筛选越精确,越难识别出手掌,反之越容易误识别。
min_tracking_confidence:最低追踪置信度,默认值为 0.5,取值 0.0 ~ 1.0。值越大,对手掌追踪筛选越精确,越容易跟丢手掌,反之越容易误识别。
cvtColor
方法将我们的框架从BGR
重新着色到RGB
。默认情况下,OpenCV将图像颜色的格式设置为BGR
。我们需要将其设置为RGB
,因为那是mediapipe接受的格式。
process 检测
输入:RGB格式的数组
输出:multi_hand_landmarks
:每只手的关节点坐标。
multi_handedness
:每只手的手性(左/右手)。
解析 multi_hand_landmarks
,返回的坐标值为相对图片的归一化后的坐标。
landmark {
x: 0.280276567
y: 0.531350315
z: 0.00314787566
}
解析 multi_handedness
,返回:序号、置信度、手性。
classification {
index: 0
score: 0.994448185
label: "Left"
}
函数 draw_landmarks
在图片中绘制关节点和骨骼,接收6个输入参数:
image:BGR 三通道 numpy 数组;
landmark_list:需要标注在图片上的、标准化后的关节点列表(landmark_pb2.NormalizedLandmarkList);
connections:关节点索引列表,指定关节点连接方式,默认值为 None,不绘制;
landmark_drawing_spec:指定关节点的绘图设定,输入可以是 DrawingSpec 或者 Mapping[int, DrawingSpec],传入 None 时不绘制关节点,默认值为 DrawingSpec(color=RED_COLOR);
connection_drawing_spec:指定骨骼的绘制设定,输入可以是 DrawingSpec 或者 Mapping[int, DrawingSpec],传入 None 时不绘制关节点,默认值为 DrawingSpec();
is_drawing_landmarks:是否绘制关节点,默认值为 True。
测试代码:来自手部21个关键点检测+手势识别-[MediaPipe]_手部关键点检测-CSDN博客
import cv2
import mediapipe as mpmp_drawing = mp.solutions.drawing_utils
mp_hands = mp.solutions.hands
#手部模型
hands = mp_hands.Hands(static_image_mode=False,max_num_hands=2,min_detection_confidence=0.75,min_tracking_confidence=0.75)cap = cv2.VideoCapture(0)#打开默认摄像头
while True:ret,frame = cap.read()#读取一帧图像#图像格式转换frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)# 因为摄像头是镜像的,所以将摄像头水平翻转# 不是镜像的可以不翻转frame= cv2.flip(frame,1)#输出结果results = hands.process(frame)frame = cv2.cvtColor(frame, cv2.COLOR_RGB2BGR)if results.multi_handedness:for hand_label in results.multi_handedness:print(hand_label)if results.multi_hand_landmarks:for hand_landmarks in results.multi_hand_landmarks:print(f'hand_landmarks:{hand_landmarks}' )# 关键点可视化mp_drawing.draw_landmarks(frame, hand_landmarks, mp_hands.HAND_CONNECTIONS)cv2.imshow('MediaPipe Hands', frame)if cv2.waitKey(1) & 0xFF == 27:break
cap.release()
效果:
看到这里,就对手部检测有个基本的了解。
接下来,看看亚博的小车如何在捕获摄像头画面做手部检测的。
三 手部检测代码
src/yahboom_esp32_mediapipe/yahboom_esp32_mediapipe/目录下01_HandDetector.py
import rclpy
import time
import mediapipe as mp
import cv2 as cv
from rclpy.node import Node
from geometry_msgs.msg import Point
from cv_bridge import CvBridge
from sensor_msgs.msg import Image, CompressedImagefrom rclpy.time import Time
import datetime#import define msg
from yahboomcar_msgs.msg import PointArray
import numpy as np
print("import done")class HandDetector(Node):def __init__(self, name, mode=False, maxHands=2, detectorCon=0.5, trackCon=0.5):super().__init__(name)self.mpHand = mp.solutions.handsself.mpDraw = mp.solutions.drawing_utils#手部检测模型self.hands = self.mpHand.Hands(static_image_mode=mode,max_num_hands=maxHands,min_detection_confidence=detectorCon,min_tracking_confidence=trackCon)#在图片或视频中绘制出姿态关键点样式:线宽、颜色self.lmDrawSpec = mp.solutions.drawing_utils.DrawingSpec(color=(0, 0, 255), thickness=-1, circle_radius=6)self.drawSpec = mp.solutions.drawing_utils.DrawingSpec(color=(0, 255, 0), thickness=2, circle_radius=2)# create a publisherself.pub_point = self.create_publisher(PointArray, '/mediapipe/points', 1000)#瘦不检测def pubHandsPoint(self, frame, draw=True):pointArray = PointArray()img = np.copy(frame)#图片格式转换img_RGB = cv.cvtColor(frame, cv.COLOR_BGR2RGB)#进行检测self.results = self.hands.process(img_RGB)if self.results.multi_hand_landmarks:#关键点处理for i in range(len(self.results.multi_hand_landmarks)):if draw: #关键点输出self.mpDraw.draw_landmarks(frame, self.results.multi_hand_landmarks[i], self.mpHand.HAND_CONNECTIONS, self.lmDrawSpec, self.drawSpec)self.mpDraw.draw_landmarks(img, self.results.multi_hand_landmarks[i], self.mpHand.HAND_CONNECTIONS, self.lmDrawSpec, self.drawSpec)for id, lm in enumerate(self.results.multi_hand_landmarks[i].landmark):point = Point()point.x, point.y, point.z = lm.x, lm.y, lm.zpointArray.points.append(point)self.pub_point.publish(pointArray) #发布关键点话题return frame, imgdef frame_combine(slef, frame, src):if len(frame.shape) == 3:frameH, frameW = frame.shape[:2]srcH, srcW = src.shape[:2]dst = np.zeros((max(frameH, srcH), frameW + srcW, 3), np.uint8)dst[:, :frameW] = frame[:, :]dst[:, frameW:] = src[:, :]else:src = cv.cvtColor(src, cv.COLOR_BGR2GRAY)frameH, frameW = frame.shape[:2]imgH, imgW = src.shape[:2]dst = np.zeros((frameH, frameW + imgW), np.uint8)dst[:, :frameW] = frame[:, :]dst[:, frameW:] = src[:, :]return dstclass MY_Picture(Node):def __init__(self, name):super().__init__(name)self.bridge = CvBridge()self.sub_img = self.create_subscription(CompressedImage, '/espRos/esp32camera', self.handleTopic, 1) #获取esp32传来的图像self.last_stamp = Noneself.new_seconds = 0self.fps_seconds = 1self.hand_detector = HandDetector('hand_detector')#图像回调函数def handleTopic(self, msg):self.last_stamp = msg.header.stamp if self.last_stamp:total_secs = Time(nanoseconds=self.last_stamp.nanosec, seconds=self.last_stamp.sec).nanosecondsdelta = datetime.timedelta(seconds=total_secs * 1e-9)seconds = delta.total_seconds()*100if self.new_seconds != 0:self.fps_seconds = seconds - self.new_secondsself.new_seconds = seconds#保留这次的值start = time.time()frame = self.bridge.compressed_imgmsg_to_cv2(msg)frame = cv.resize(frame, (640, 480))cv.waitKey(10)#调用手部检测frame, img = self.hand_detector.pubHandsPoint(frame, draw=False)end = time.time()fps = 1/((end - start)+self.fps_seconds) text = "FPS : " + str(int(fps))cv.putText(frame, text, (20, 30), cv.FONT_HERSHEY_SIMPLEX, 0.9, (0, 0, 255), 1)#显示dist = self.hand_detector.frame_combine(frame, img)cv.imshow('dist', dist)# print(frame)cv.waitKey(10)def main():print("start it")rclpy.init()esp_img = MY_Picture("My_Picture")try:rclpy.spin(esp_img)except KeyboardInterrupt:passfinally:esp_img.destroy_node()rclpy.shutdown()
代码稍微长点,可以认为是分成了2部分,主节点是MY_Picture。
MY_Picture 里面首先获取摄像头画面,逻辑跟上一篇类似。
获取完之后,调用手部检测pubHandsPoint方法,反悔了原始图像跟加节点的图像。
最后展示。
bohu@bohu-TM1701:~/yahboomcar/yahboomcar_ws$ ros2 run yahboom_esp32_mediapipe HandDetector
import done
start it
WARNING: All log messages before absl::InitializeLog() is called are written to STDERR
I0000 00:00:1737441363.353163 46594 gl_context_egl.cc:85] Successfully initialized EGL. Major : 1 Minor: 5
I0000 00:00:1737441363.357023 46653 gl_context.cc:369] GL version: 3.2 (OpenGL ES 3.2 Mesa 23.2.1-1ubuntu3.1~22.04.3), renderer: Mesa Intel(R) UHD Graphics 620 (KBL GT2)
INFO: Created TensorFlow Lite XNNPACK delegate for CPU.
W0000 00:00:1737441363.415742 46637 inference_feedback_manager.cc:114] Feedback manager requires a model with a single signature inference. Disabling support for feedback tensors.
W0000 00:00:1737441363.449011 46633 inference_feedback_manager.cc:114] Feedback manager requires a model with a single signature inference. Disabling support for feedback tensors.
W0000 00:00:1737441363.466042 46634 landmark_projection_calculator.cc:186] Using NORM_RECT without IMAGE_DIMENSIONS is only supported for the square ROI. Provide IMAGE_DIMENSIONS or use PROJECTION_MATRIX.
Warning: Ignoring XDG_SESSION_TYPE=wayland on Gnome. Use QT_QPA_PLATFORM=wayland to run on Wayland anyway.
效果如下
我觉得官方的图黑乎乎的,还不如在原图上加节点直观,改了下
相关文章:

亚博microros小车-原生ubuntu支持系列:4-手部检测
一 准备工作 在学习手部检测之前,有2个准备工作。 1 确保小车的摄像头能显示画面 参见:亚博microros小车-原生ubuntu支持系列:2-摄像头控制-CSDN博客 启动图传代理: docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm …...
关于回调函数(callback)
简介 在C中,回调函数是一种常见的编程技术,它允许你将一个函数作为参数传递给另一个函数,并在适当的时候调用它。回调函数通常用于事件处理、异步编程和模块化设计中。 1、函数指针:在C中,回调函数通常是通过函数指针…...

Linux Bash 中使用重定向运算符的 5 种方法
注:机翻,未校。 Five ways to use redirect operators in Bash Posted: January 22, 2021 | by Damon Garn Redirect operators are a basic but essential part of working at the Bash command line. See how to safely redirect input and output t…...

硬件作品3----STM32F103RCT6最小系统板MCU配置
参考文章:对stm32F103RCT6原理图解析(详细)-CSDN博客 本想绘制稍微复杂一些的电路,但是出现很多问题,因此先绘制一块最小系统板进行原理、绘制方法的验证。 设计难度:★ 适合人群:初学者 一、…...

人脸识别打卡系统--基于QT(附源码)
逃离舒适区 项目源代码放在我的仓库中,有需要自取 项目地址 https://gitcode.com/hujiahangdewa/Face_recognition.git 文章目录 一、项目结构分析二、服务器的搭建三、客户端的搭建四、人脸识别库的申请五、基于人脸识别库的识别判断六、QT人脸识别----调用百度ai…...
【深度学习入门】深度学习知识点总结
一、卷积 (1)什么是卷积 定义:特征图的局部与卷积核做内积的操作。 作用:① 广泛应用于图像处理领域。卷积操作可以提取图片中的特征,低层的卷积层提取局部特征,如:边缘、线条、角。 ② 高层…...

通过视觉语言模型蒸馏进行 3D 形状零件分割
大家读完觉得有帮助记得关注和点赞!!!对应英文要求比较高,特此说明! Abstract This paper proposes a cross-modal distillation framework, PartDistill, which transfers 2D knowledge from vision-language models …...

机器学习10-解读CNN代码Pytorch版
机器学习10-解读CNN代码Pytorch版 我个人是Java程序员,关于Python代码的使用过程中的相关代码事项,在此进行记录 文章目录 机器学习10-解读CNN代码Pytorch版1-核心逻辑脉络2-参考网址3-解读CNN代码Pytorch版本1-MNIST数据集读取2-CNN网络的定义1-无注释版…...

微服务学习-Gateway 统一微服务入口
1. 微服务为什么需要 API 网关? 1.1. 在微服务架构中,通常一个系统会被拆分为多个微服务,面对多个微服务客户端应该如何去调用呢? 如果根据每个微服务的地址发起调用,存在如下问题: 客户端多次请求不同的…...

2025寒假备战蓝桥杯02---朴素二分查找升级版本的学习+分别求解左右端点
文章目录 1.朴素二分查找的升级版2.查找左端点3.查找右端点4.代码的编写 1.朴素二分查找的升级版 和之前介绍的这个二分查找相比,我觉得这个区别就是我们的这个二分查找需要找到的是一个区间,而不是这个区间里面的某一个元素的位置; 2.查找…...
PHP语言的软件工程
PHP语言的软件工程 引言 软件工程是计算机科学中的一个重要分支,它涉及软件的规划、开发、测试和维护。在现代开发中,PHP作为一种流行的服务器端脚本语言,广泛应用于网页开发和各种企业应用中。本文将深入探讨PHP语言在软件工程中的应用&am…...

linux-FTP服务配置与应用
也许你对FTP不陌生,但是你是否了解FTP到底是个什么玩意? FTP 是File Transfer Protocol(文件传输协议)的英文简称,而中文简称为 “文传协议” 用于Internet上的控制文件的双向传输。同时,它也是一个应用程序…...

靠右行驶数学建模分析(2014MCM美赛A题)
笔记 题目 要求分析: 比较规则的性能,分为light和heavy两种情况,性能指的是 a.流量与安全 b. 速度限制等分析左侧驾驶分析智能系统 论文 参考论文 两类规则分析 靠右行驶(第一条)2. 无限制(去掉了第一条…...

(1)STM32 USB设备开发-基础知识
开篇感谢: 【经验分享】STM32 USB相关知识扫盲 - STM32团队 ST意法半导体中文论坛 单片机学习记录_桃成蹊2.0的博客-CSDN博客 USB_不吃鱼的猫丿的博客-CSDN博客 1、USB鼠标_哔哩哔哩_bilibili usb_冰糖葫的博客-CSDN博客 USB_lqonlylove的博客-CSDN博客 USB …...

Spring中如何动态的创建、监听MQ以及创建Exchange
文章目录 前言动态创建和管理Exchange、Queue动态消费Queue结论 前言 前面我们学习 RabbitMQ 的时候,都是在编译的时候就确定了Exchange、Queue,也就是说我们需要在程序启动之前就创建好需要的Exchange和Queue,但是实际使用的时候࿰…...

中国综合算力指数(2024年)报告汇总PDF洞察(附原数据表)
原文链接: https://tecdat.cn/?p39061 在全球算力因数字化技术发展而竞争加剧,我国积极推进算力发展并将综合算力作为数字经济核心驱动力的背景下,该报告对我国综合算力进行研究。 中国算力大会发布的《中国综合算力指数(2024年…...

【Python项目】小区监控图像拼接系统
【Python项目】小区监控图像拼接系统 技术简介:采用Python技术、B/S框架、MYSQL数据库等实现。 系统简介:小区监控拼接系统,就是为了能够让业主或者安保人员能够在同一时间将不同地方的图像进行拼接。这样一来,可以很大程度的方便…...

常用排序算法之插入排序
目录 前言 一、基本原理 1.算法步骤 2.动画演示 3.插入排序的实现代码 二、插入排序的时间复杂度 1. 时间复杂度 1.最优时间复杂度 2.最差时间复杂度 3.平均时间复杂度 2. 空间复杂度 三、插入排序的优缺点 1.优点 2.缺点 四、插入排序的改进与变种 五、插入排…...
Elasticsearch(ES)基础查询语法的使用
1. Match Query (全文检索查询) 用于执行全文检索,适合搜索文本字段。 { “query”: { “match”: { “field”: “value” } } } match_phrase:精确匹配短语,适合用于短语搜索。 { “query”: { “match_phrase”: { “field”: “text” }…...

一篇文章学会Milvus【Docker 中运行 Milvus(Windows),Python实现对Milvus的操作,源代码案例,已经解决巨坑】【程序员猫爪】
一篇文章学会Milvus【Docker 中运行 Milvus(Windows),Python实现对Milvus的操作,源代码案例,已经解决巨坑】【程序员猫爪】 一、Milvus 是什么?【程序员猫爪】1、Milvus 是一种高性能、高扩展性的向量数据库…...

SpringBoot-17-MyBatis动态SQL标签之常用标签
文章目录 1 代码1.1 实体User.java1.2 接口UserMapper.java1.3 映射UserMapper.xml1.3.1 标签if1.3.2 标签if和where1.3.3 标签choose和when和otherwise1.4 UserController.java2 常用动态SQL标签2.1 标签set2.1.1 UserMapper.java2.1.2 UserMapper.xml2.1.3 UserController.ja…...

wordpress后台更新后 前端没变化的解决方法
使用siteground主机的wordpress网站,会出现更新了网站内容和修改了php模板文件、js文件、css文件、图片文件后,网站没有变化的情况。 不熟悉siteground主机的新手,遇到这个问题,就很抓狂,明明是哪都没操作错误&#x…...
Android Wi-Fi 连接失败日志分析
1. Android wifi 关键日志总结 (1) Wi-Fi 断开 (CTRL-EVENT-DISCONNECTED reason3) 日志相关部分: 06-05 10:48:40.987 943 943 I wpa_supplicant: wlan0: CTRL-EVENT-DISCONNECTED bssid44:9b:c1:57:a8:90 reason3 locally_generated1解析: CTR…...

JavaScript 中的 ES|QL:利用 Apache Arrow 工具
作者:来自 Elastic Jeffrey Rengifo 学习如何将 ES|QL 与 JavaScript 的 Apache Arrow 客户端工具一起使用。 想获得 Elastic 认证吗?了解下一期 Elasticsearch Engineer 培训的时间吧! Elasticsearch 拥有众多新功能,助你为自己…...
Admin.Net中的消息通信SignalR解释
定义集线器接口 IOnlineUserHub public interface IOnlineUserHub {/// 在线用户列表Task OnlineUserList(OnlineUserList context);/// 强制下线Task ForceOffline(object context);/// 发布站内消息Task PublicNotice(SysNotice context);/// 接收消息Task ReceiveMessage(…...

苍穹外卖--缓存菜品
1.问题说明 用户端小程序展示的菜品数据都是通过查询数据库获得,如果用户端访问量比较大,数据库访问压力随之增大 2.实现思路 通过Redis来缓存菜品数据,减少数据库查询操作。 缓存逻辑分析: ①每个分类下的菜品保持一份缓存数据…...

select、poll、epoll 与 Reactor 模式
在高并发网络编程领域,高效处理大量连接和 I/O 事件是系统性能的关键。select、poll、epoll 作为 I/O 多路复用技术的代表,以及基于它们实现的 Reactor 模式,为开发者提供了强大的工具。本文将深入探讨这些技术的底层原理、优缺点。 一、I…...
全面解析各类VPN技术:GRE、IPsec、L2TP、SSL与MPLS VPN对比
目录 引言 VPN技术概述 GRE VPN 3.1 GRE封装结构 3.2 GRE的应用场景 GRE over IPsec 4.1 GRE over IPsec封装结构 4.2 为什么使用GRE over IPsec? IPsec VPN 5.1 IPsec传输模式(Transport Mode) 5.2 IPsec隧道模式(Tunne…...

如何在网页里填写 PDF 表格?
有时候,你可能希望用户能在你的网站上填写 PDF 表单。然而,这件事并不简单,因为 PDF 并不是一种原生的网页格式。虽然浏览器可以显示 PDF 文件,但原生并不支持编辑或填写它们。更糟的是,如果你想收集表单数据ÿ…...
Pinocchio 库详解及其在足式机器人上的应用
Pinocchio 库详解及其在足式机器人上的应用 Pinocchio (Pinocchio is not only a nose) 是一个开源的 C 库,专门用于快速计算机器人模型的正向运动学、逆向运动学、雅可比矩阵、动力学和动力学导数。它主要关注效率和准确性,并提供了一个通用的框架&…...