一. 环境介绍
(一)积木分拣
1、pcl 1.11.1
2、OpenCV
3、Visual Studio 2019
4、VTK 8.2
5、QT 5.13.2
二. 积木分拣
本文主要介绍研究进展(三)中积木分拣项目的QT上位机部分程序及上位机与机器人通信的相关内容
HK_Robot_Materials_Sorting.h
class HK_Robot_Materials_Sorting : public QWidget
{
Q_OBJECT
public:
SOCKET robot_socket;
HK_Robot_Materials_Sorting(QWidget *parent = nullptr);
~HK_Robot_Materials_Sorting();
unsigned int nDevNum = 0;
Mv3dRgbdDeviceType device_type;
std::vector devs;//设备列表
boost::shared_ptr viewer;
boost::shared_ptr viewer1;
pcl::PointCloud cloud;
typedef pcl::PointXYZRGB PointT;
typedef pcl::PointCloudPointCloud;
PointCloud::Ptr cloudRGB;
private slots:
void on_btnFinddevice_clicked();
void on_btnOpenDevice_clicked();
void on_btngrap_clicked();
void on_btnSelectBegin_clicked();
void on_pushButton_2_clicked();
void on_btn_stop_clicked();
void on_btn_auto_clicked();
void onServerStatusChanged(const QString& statusMessage);
public:
void grap_show(void * handle );
void grap_show_auto(void* handle);
void* handle = NULL;
unsigned char* g_pRgbData = NULL;
bool ConvertRGB8Planner2BGR8Packed(const unsigned char* pSrcData, int nWidth,int nHeight,unsigned char* pDstData);
void VTK_Init();
MV3D_RGBD_IMAGE_DATA imgCloud;
void color_selece();
Eigen::Matrix4f Matrix_A;
Eigen::Matrix4f Matrix_B;
bool robotflag;
MyRobot* robot;
private:
Ui::HK_Robot_Materials_SortingClass ui;
};
该部分主要为上位机与机器人通信的相关程序
MyRobot.h
class MyRobot :
public QObject
{
Q_OBJECT
signals:
void serverStatusChanged(const QString& statusMessage);
public:
explicit MyRobot(QObject* parent = nullptr);
void startServer();
void sendDataToClient(int clientIndex, const QString& message);
void Send(QTcpSocket* socket, const QString& message);
private slots:
void onNewConnection();
void onSocketReadyRead();
private:
QTcpServer* m_server;
QList m_clients;
QTcpSocket* client;
};
MyRobot.cpp
#include "MyRobot.h"
#include
MyRobot::MyRobot(QObject* parent) : QObject(parent),
m_server(new QTcpServer(this))
{
connect(m_server,&QTcpServer::newConnection, this,&MyRobot::onNewConnection);
}
void MyRobot::startServer()
{
if (m_server->listen(QHostAddress("192.168.1.200"), 6000))
{
emit serverStatusChanged(u8"服务器创建成功\n");
}
else
{
emit serverStatusChanged(u8"请检查robot的IP和端口\n");
}
}
void MyRobot::onNewConnection()
{
QTcpSocket* client = m_server->nextPendingConnection();
m_clients.append(client);
connect(client, &QTcpSocket::readyRead, this, &MyRobot::onSocketReadyRead);
emit serverStatusChanged(u8"有客户端接入\n");
}
void MyRobot::onSocketReadyRead()
{
QTcpSocket* client = qobject_cast(sender());
if (client)
{
QByteArray data = client->readAll();
QString str = QString::fromUtf8(data);
if (str == "6")
{
emit serverStatusChanged(u8"6");
}
}
}
void MyRobot::Send(QTcpSocket* socket, const QString& message)
{
socket->write(message.toUtf8());
socket->waitForBytesWritten();
}
void MyRobot::sendDataToClient(int clientIndex, const QString& message)
{
if (clientIndex >= 0 && clientIndex < m_clients.size())
{
Send(m_clients.at(clientIndex), message);
}
}
与研究进展(二)使用winform编写的鞋底分拣上位机程序一样,这里同样采用机械臂作为客户端,上位机作为服务器,当用户点击自动运行按钮后,相机会进行拍照并通过PCL进行点云处理,并将得到的抓取坐标发送给机械臂,第一次抓拍之后的所有拍照操作由客户端控制,当机械臂第一次获取的所有坐标全部抓取完毕后,机械臂运动到最后一个物料的放料区域的同时会向上位机发送一个数字6,上位机接收到数字6会触发信号serverStatusChanged,并去执行对应的槽函数 抓拍点云数据并进行点云处理,将得到的抓取坐标发送给客户端,客户端会解析数据,引导机械臂进行抓取。
void HK_Robot_Materials_Sorting::on_btn_auto_clicked()
{
ca_fl == true;
btn_flag = true;
if ((firstcamera == true && btn_flag == true))
{
firstcamera = false;
grap_show_auto(handle);
}
}
void HK_Robot_Materials_Sorting::onServerStatusChanged(const QString& statusMessage)
{ if (statusMessage == "6"&& firstcamera == false && btn_flag == true&& ca_fl == true)
{ ui.textBrowser_3->insertPlainText(u8"success");
grap_show_auto(handle);
}
}
点云处理程序之前已经进行了介绍这里不在详细介绍
ui.textBrowser->clear();
pcl::PassThrough pass;//设置滤波器对象
pass.setInputCloud(cloudRGB);
pass.setFilterFieldName("z");//设置滤波方向
pass.setFilterLimits(500, 750);
pass.setFilterLimitsNegative(false);
pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud());
pass.filter(*cloud_out);
pass.setInputCloud(cloud_out);
pass.setFilterFieldName("x");
pass.setFilterLimits(-330,70);
pass.filter(*cloud_out);
pass.setInputCloud(cloud_out);
pass.setFilterFieldName("y");
pass.setFilterLimits(-400, 100);
pass.filter(*cloud_out); // 执行过滤操作
pcl::io::savePCDFileASCII("xx.pcd", *cloud_out);
//统计滤波
pcl::StatisticalOutlierRemoval outrem;//创建统计滤波对象
outrem.setInputCloud(cloud_out);
outrem.setMeanK(800);//附近邻近点数
outrem.setStddevMulThresh(1);//标准差系数
pcl::PointCloud::Ptr cloud_out1(new pcl::PointCloud);
outrem.filter(*cloud_out1);
std::vector vecX;
std::vector vecY;
std::vector vecZ;
std::vector vecflag;
pcl::PointCloud::Ptr redfilteredCloud(new pcl::PointCloud);
pcl::PointCloud::Ptr greenfilteredCloud(new pcl::PointCloud);
pcl::PointCloud::Ptr bluefilteredCloud(new pcl::PointCloud);
pcl::PointCloud::Ptr orginfilteredCloud(new pcl::PointCloud);
pcl::PointCloud::Ptr allpointcloud(new pcl::PointCloud);
std::vector::Ptr> cloudList;
Eigen::Vector4f centroid;
string color_flag;
pcl::PointXYZ center;
for (size_t i = 0; i < cloud_out1->points.size(); ++i) {
const pcl::PointXYZRGB& point = cloud_out1->points[i];
if (point.r >= 200 && point.r <= 255 && point.g >=60 && point.g <= 100 && point.b >= 10 && point.b <= 60)
{
redfilteredCloud->points.push_back(point);
allpointcloud->points.push_back(point);
}
}
for (size_t i = 0; i < cloud_out1->points.size(); ++i) {
const pcl::PointXYZRGB& point = cloud_out1->points[i];
if (point.r >= 140 && point.r <= 190 && point.g >= 210 && point.g <= 255 && point.b >= 80 && point.b <= 130) {
greenfilteredCloud->points.push_back(point);
allpointcloud->points.push_back(point);
}
}
for (size_t i = 0; i < cloud_out1->points.size(); ++i) {
const pcl::PointXYZRGB& point = cloud_out1->points[i];
if (point.r >= 80 && point.r <= 120 && point.g >= 180 && point.g <= 210 && point.b >= 230) {
bluefilteredCloud->points.push_back(point);
allpointcloud->points.push_back(point);
}
}
for (size_t i = 0; i < cloud_out1->points.size(); ++i) {
const pcl::PointXYZRGB& point = cloud_out1->points[i];
if (point.r >= 230 && point.g >= 160 && point.g <= 190 && point.b >= 60 && point.b <= 100) {
orginfilteredCloud->points.push_back(point);
allpointcloud->points.push_back(point);
}
} allpointcloud->width = allpointcloud->points.size();
allpointcloud->height = 1;
redfilteredCloud->width = redfilteredCloud->points.size();
redfilteredCloud->height = 1;
greenfilteredCloud->width = greenfilteredCloud->points.size();
greenfilteredCloud->height = 1;
bluefilteredCloud->width = bluefilteredCloud->points.size();
bluefilteredCloud->height = 1;
orginfilteredCloud->width = orginfilteredCloud->points.size();
orginfilteredCloud->height = 1;
cloudList.push_back(redfilteredCloud);
cloudList.push_back(greenfilteredCloud);
cloudList.push_back(bluefilteredCloud);
cloudList.push_back(orginfilteredCloud);
for (size_t k = 0; k < cloudList.size(); ++k) {
if(900points.size()<=1400)
{
pcl::compute3DCentroid(*cloudList[k], centroid);
vecX.push_back(centroid(0));
vecY.push_back(centroid(1));
vecZ.push_back(centroid(2));
if (k == 0)
{
vecflag.push_back('R');
}
else if (k == 1)
{
vecflag.push_back('G');
}
else if (k == 2)
{
vecflag.push_back('B');
}
else if (k == 3)
{
vecflag.push_back('O');
}
}
else if(cloudList[k]->points.size()>1400)
{
pcl::search::KdTree::Ptr tree(new pcl::search::KdTree);
tree->setInputCloud(cloud_out);
std::vector::Ptr> result;
std::vector cluster_indices;
pcl::EuclideanClusterExtraction ec;
ec.setClusterTolerance(1.4);
ec.setMinClusterSize(650);
ec.setMaxClusterSize(2000);
ec.setSearchMethod(tree);
ec.setInputCloud(cloud_out);
ec.extract(cluster_indices);
std::vector::Ptr> Eucluextra;
for (std::vector::const_iterator it = cluster_indices.begin(); it != cluster_indices.end(); ++it)
{
pcl::PointCloud::Ptr cloud_cluster1(new pcl::PointCloud);
for (std::vector::const_iterator pit = it->indices.begin(); pit != it->indices.end(); pit++)
cloud_cluster1->points.push_back(cloud_out->points[*pit]);
cloud_cluster1->width = cloud_cluster1->points.size();
cloud_cluster1->height = 1;
cloud_cluster1->is_dense = true;
Eucluextra.push_back(cloud_cluster1);
}
for (int t = 0; t < Eucluextra.size(); t++)
{
pcl::compute3DCentroid(*Eucluextra[t], centroid);
vecX.push_back(centroid(0));
vecY.push_back(centroid(1));
vecZ.push_back(centroid(2));
}
if (k == 0)
{
vecflag.push_back('R');
}
else if (k == 1)
{
vecflag.push_back('G');
}
else if (k == 2)
{
vecflag.push_back('B');
}
else if (k == 3)
{
vecflag.push_back('O');
}
}
}
for (size_t i = 0; i < vecX.size(); ++i) {
char color =vecflag[i];
QString colorchinese;
if (color == 'R')
{
colorchinese = u8"红色";
}
else if (color == 'G')
{
colorchinese = u8"绿色";
}
else if (color == 'B')
{
colorchinese = u8"蓝色";
}
else if (color == 'O')
{
colorchinese = u8"橙色";
}
pcl::PointXYZ o;
o.x = vecX[i];
o.y = vecY[i];
o.z = vecZ[i];
viewer1->addSphere(o, 3, 255, 255, 101, std::to_string(i*3), 0);
Eigen::Vector4f eigen_vector(vecX[i], vecY[i], vecZ[i], 0);
Eigen::Vector4f resulat = Matrix_A* eigen_vector;
Eigen::Vector4f resultS = Matrix_B * resulat;
float jx = 744.50;
float jy = 304.77;
float jz = -38.90;
float cx = 105.976;
float cy = 6.337556;
float cz = 4.744299;
float px = jx - cx;
float py = jy - cy;
float pz = jz - cz;
float x = resultS[0] + px;
float y= resultS[1] + py;
float z = resultS[2] + pz; //由于积木为正方形 所以每次以固定姿态抓取即可,所以这里没有计算姿态,以固定姿态进行抓取
QString canshu = QString(u8"颜色:""%1"" X:""%2"" Y:""%3"" Z:""%4\n").arg(colorchinese).arg(x).arg(y).arg(z);
QString txt = "("+QString::number(color) + QString::number(x) + "," + QString::number(y) + "," + QString::number(z) + ")";
robot->sendDataToClient(0,txt);
ui.textBrowser->insertPlainText(canshu);
pcl::io::savePCDFile("filtered_point_cloud.pcd", *redfilteredCloud);
pcl::io::savePCDFile("greenfilteredCloud.pcd", *greenfilteredCloud);
pcl::io::savePCDFile("bluefilteredCloud.pcd", *bluefilteredCloud);
pcl::io::savePCDFile("orginfilteredCloud.pcd", *orginfilteredCloud);
viewer1->addPointCloud(allpointcloud, std::to_string(8));
viewer1->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, std::to_string(8));
ui.qvtkWidget_2->update();