效果演示

将yumi的功能模块和darknet_ros的检测模块整合到了一个工作空间,在原有食品检测分类的基础上实现了bounding boxes的获取以及抓姿的检测和发布

历史遗留问题

darknet_ros_msgs包中自定义了三种消息类型,如果和yumi的相关功能包处在不同的工作空间下yumi将无法法订阅这些自定义消息,因此必须想办法将工作空间重新整合在一起

1.

为确保配置不受编译后的文件影响,在~/catkin_ws/src下新建darknet_ros文件夹
先不要编译,重新将daknet_ros下的相关文件按上一篇博客配置好,原来的yolov3-tiny_5000.weights,ros.yaml,yolov3-tiny.yaml,yolov3-tiny.cfg,darknet_ros.launch,这些文件都要搬到当前的darknet_ros里面来

2.

准备好这些后就可以开始编译了

1
2
cd ~/catkin_ws
catkin_make -DCATKIN_WHITELIST_PACKAGES=“darknet;darknet_ros;darknet_ros_msgs” -DCMAKE_BUILD_TYPE=Release

3.

编译好后在其它功能包创建的时候就可以用到darknet_ros_msgs里面自定义消息啦

这里我们新建一个功能包用于抓姿检测

1
2
3
4
cd ~/catkin_ws/src
catkin_create_pkg yoloproc darknet_ros_msgs roscpp rospy std_msgs
cd ..
catkin_make -DCATKIN_WHITELIST_PACKAGES='yoloproc'

编译完成之后,python代码就可以直接 from darknet_ros_msgs.msg import BoundingBoxes

检查~/catkin_ws工作空间的文件结构

生成文件结构用到tree

tree -L 2 > /home/li/tree.txt

生成结果保存到了tree.txt,内容如下

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
.
├── CMakeLists.txt -> /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake
├── darknet_ros
│   ├── darknet
│   ├── darknet_ros
│   ├── darknet_ros_msgs
│   ├── jenkins-pipeline
│   ├── LICENSE
│   └── README.md
├── gazebo_mimic
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── include
│   ├── package.xml
│   ├── README.md
│   └── src
├── README
├── yoloproc
│   ├── CMakeLists.txt
│   ├── include
│   ├── package.xml
│   └── src
├── yumi_control
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── config
│   └── package.xml
├── yumi_description
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── meshes
│   ├── package.xml
│   ├── README.md
│   └── urdf
├── yumi_hw
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── include
│   ├── launch
│   ├── package.xml
│   ├── rapid
│   ├── scripts
│   ├── src
│   └── srv
├── yumi_launch
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── launch
│   ├── package.xml
│   └── worlds
├── yumi_moveit_config
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── config
│   ├── launch
│   └── package.xml
├── yumi_support
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── config
│   ├── launch
│   ├── package.xml
│   └── rapid
└── yumi_test_controllers
├── CMakeLists.txt
├── include
├── package.xml
├── scripts
└── src

36 directories, 32 files

基于RGB图像的平面抓姿检测

主要思路根据yolov3-tiny的预测框对检测出的物体依次进行图像阈值分割,轮廓提取,利用图像矩求重心和主方向(这里也可以尝试PCA主成分分析),最后由重心和主方向计算抓姿

在windows PyCharm上编写好抓姿检测的代码后移植到了linux下的ROS中

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
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
import cv2
import math
import cv_bridge
import numpy as np
import message_filters
from sensor_msgs.msg import Image
from darknet_ros_msgs.msg import BoundingBoxes
from darknet_ros_msgs.msg import ObjectCount
import message_filters
from cv_bridge import CvBridge, CvBridgeError


def find_pose(contour, flag):
mu = cv2.moments(contour, flag)
x = mu['m10'] / mu['m00']
y = mu['m01'] / mu['m00']
a = mu['m20'] / mu['m00'] - x * x
b = mu['m11'] / mu['m00'] - x * y
c = mu['m02'] / mu['m00'] - y * y
Angle = math.atan2(2 * b, (a - c)) / 2
return x, y, Angle


def draw_grasp_line(image2, w, h, x, y, ang):
# 画线宽度为最小外接矩形宽度的1.3倍
h = 1.3 * h
ver_ang = (90 - abs(ang)) * math.pi / 180
if w < h:
w, h = h, w
sin_ver_ang = math.sin(ver_ang)
cos_ver_ang = math.cos(ver_ang)
# print(sin_ver_ang*h / 2,sin_ver_ang*h / 2)
# 确定垂直主轴的一条线段
if ang < 0:
A_x = int(x - cos_ver_ang * h / 2)
B_x = int(x + cos_ver_ang * h / 2)
A_y = int(y + sin_ver_ang * h / 2)
B_y = int(y - sin_ver_ang * h / 2)
else:
A_x = int(x - cos_ver_ang * h / 2)
B_x = int(x + cos_ver_ang * h / 2)
A_y = int(y - sin_ver_ang * h / 2)
B_y = int(y + sin_ver_ang * h / 2)
A = (A_x, A_y)
B = (B_x, B_y)
# print(x,y)
# print(A,B)
cv2.line(image2, A, B, (0, 0, 255), 5, 8)

return

def img_proc(image, position_list):
img_proc_list = []
# print(img_proc_list)
for i in range(len(position_list)):
img = image[position_list[i][2]:position_list[i][4],position_list[i][1]: position_list[i][3]]
# cv2.imshow('cropped',img)剪裁分块处理
img2 = cv2.GaussianBlur(img, (3, 3), 0)
# cv2.imshow('blurred', img2)高斯模糊滤波
img3 = cv2.cvtColor(img2, cv2.COLOR_BGR2GRAY)
retval, img4 = cv2.threshold(img3, 232, 255, cv2.THRESH_BINARY_INV)
# cv2.imshow('gray and binary', img4)灰度化二值化
# img5 = cv2.Canny(img4, 50, 150)Canny边缘检测
#检测轮廓
binary,contours, hierarchy = cv2.findContours(img4, cv2.RETR_TREE, cv2.CHAIN_APPROX_NONE)
n = len(contours) # 轮廓的个数
contours_area = []
# 找到最大的轮廓
for j in range(len(contours)):
contours_area.append(cv2.contourArea(contours[j]))
max_id = np.argmax(np.array(contours_area))
# print(max_id)
# 画轮廓
cv2.drawContours(img, contours, max_id, (0, 255, 0), 3)
# 图像矩找重心和主方向
center_x, center_y, angle = find_pose(contours[max_id], False)
# 数据类型转换
inverse_angle2 = -round(angle * 180 / math.pi, 1)
int_center_x = int(center_x)
int_center_y = int(center_y)
# 画重心
cv2.circle(img, (int_center_x, int_center_y), 5, (0, 0, 255), -1)
# print(int_center_x, int_center_y, inverse_angle2)
# cv2.imshow('contours', img)
# 4.获取最小外接矩形并打印
min_rect = cv2.minAreaRect(contours[max_id])
min_rect_height = int(min_rect[1][1])
min_rect_width = int(min_rect[1][0])
# rect_points = cv2.boxPoints(min_rect)
# rect_points = np.int0(rect_points)
# # print(min_rect_width)
# cv2.drawContours(img, [rect_points], 0, (0, 255, 0), 3)
# 画出抓取线
draw_grasp_line(img, min_rect_width, min_rect_height, int_center_x, int_center_y, inverse_angle2)
# 图像处理好后把抓取中心坐标加上左上角的x,y坐标得出实际的坐标
int_center_x = int_center_x + int(position_list[i][1])
int_center_y = int_center_y + int(position_list[i][2])
# 存放类别和抓取位姿信息
img_proc_list.append([position_list[i][0], int_center_x, int_center_y, inverse_angle2])
#print(img_proc_list[i][0])
#print(str(int_center_x))
#print(img_proc_list)
#cv2.imshow('gasp line', image)
#cv2.waitKey(3000)

return img_proc_list,image

def multi_callback(subscriber_bounding, subscriber_image):
detected_list=[]
bridge= cv_bridge.CvBridge()
cv_image = bridge.imgmsg_to_cv2(subscriber_image, "bgr8")
frame = np.array(cv_image, dtype=np.uint8)
# cv2.imshow('Food', frame)
# cv2.waitKey(2000)
# cv2.destroyAllWindows()
#rospy.loginfo("数目是:"+str(len(subscriber_bounding.bounding_boxes)))
for i in range(len(subscriber_bounding.bounding_boxes)):
detected_list.append([subscriber_bounding.bounding_boxes[i].Class,subscriber_bounding.bounding_boxes[i].xmin,
subscriber_bounding.bounding_boxes[i].ymin,subscriber_bounding.bounding_boxes[i].xmax,subscriber_bounding.bounding_boxes[i].ymax])
#rospy.loginfo(subscriber_bounding.bounding_boxes[1].Class)
detected_result,detected_image=img_proc(cv_image, detected_list)
ros_image=bridge.cv2_to_imgmsg(detected_image, "bgr8")
image_pub.publish(ros_image)
rospy.loginfo("抓姿已生成!!!")
rospy.loginfo(detected_result)
#position_list.clear()



if __name__ == '__main__':
try:

rospy.init_node("darknet_msgs_proc")
rospy.loginfo("开始测试消息订阅....")
# GraspDetect()
image_pub=rospy.Publisher('/processed_image',Image,queue_size = 1) #定义话题
subscriber_bounding = message_filters.Subscriber('/darknet_ros/bounding_boxes', BoundingBoxes, queue_size=1)
subscriber_image = message_filters.Subscriber('/camera/color/image_raw', Image,queue_size=1)


sync = message_filters.ApproximateTimeSynchronizer([subscriber_bounding, subscriber_image],10,1)

sync.registerCallback(multi_callback)
rospy.spin()
except KeyboardInterrupt:
print("KeyboardInterrupt")
cv2.destroyAllWindows()

代码注释很详细,这里不做过多解释,需要注意的就是订阅的'/darknet_ros/bounding_boxes'/camera/color/image_raw'两个话题进行了时间戳同步,防止不同时间的相机图像与yolov3-tiny的检测结果混叠在一起,最后的检测结果包括图像和抓姿也都发布了出来

关于/darknet_ros/bounding_boxes

/darknet_ros/bounding_boxes话题的消息类型是BoundingBoxes

可以看出BoundingBoxes里面有一个数组,数组的元素是BoundingBox,格式如下

于是就可以知道如果使用里面的数据,示例:data.bounding_boxes[i].Class就代表第i个预测框里面的物体种类

遇到的问题

callback里面如果用cv2.imshow(),由于callback执行速度快且一直在循环执行,因此会造成图像显示窗口卡死,即使加上cv2.waitKey()也不太好使,于是想到一种办法将抓姿检测的结果以图片形式发布出去然后就可以在rviz里面或者通过rqt_image_view 显示发布的图片,这里我使用到了 rqt_image_view /processed_image

结果

左上角为抓姿的示意图,左下角为检测与分类结果,右下角为实时输出的抓取角度与像素坐标

相机坐标系抓姿到机器人坐标系的转换

相机标定与手眼标定,敬请期待