qt(二)

主程序入口:

#include 
#include 
#include "MainWindow.h"
int main(int argc,char *argv[]) {
    //创建程序
    QApplication app(argc,argv);
    //创建窗口
    MainWindow w;
    //显示窗口
    w.show();
    return QApplication::exec();
}

 

MainWindow.cpp代码:

//
// Created by wt on 2020/6/5.
//

#include "MainWindow.h"

MainWindow::MainWindow(QWidget* parent):QWidget(parent) {
    //初始化界面
    initUI();
    //设置回调
    setCallBack();
    //处理信号和槽
    this->bindSignalAndSlot();
}

void MainWindow::initUI() {
    setFixedSize(600, 800);
    //布局
    QFormLayout *layout = new QFormLayout;
    //ip输入框
    ipEdit = new QLineEdit("192.168.36.23");
    //端口输入框
    portEdit = new QLineEdit("30003");

    //连接状态
    statusLabel = new QLabel("未连接");

    //连接机械臂按钮
    connectBtn = new QPushButton("连接机械臂");
    disConnectBtn = new QPushButton("断开连接");

    //movej的每一个关节输入
    joint1Edit = new QLineEdit("-144.98");
    joint2Edit = new QLineEdit("-97.67");
    joint3Edit = new QLineEdit("-102.98");
    joint4Edit = new QLineEdit("-68.95");
    joint5Edit = new QLineEdit("83.07");
    joint6Edit = new QLineEdit("58.15");

    //movej
    movejBtn = new QPushButton("moveJ");

    //movel输入
    xEdit = new QLineEdit("0.99");
    yEdit = new QLineEdit("-355.35");
    zEdit = new QLineEdit("191.15");
    rxEdit = new QLineEdit("2.8321");
    ryEdit = new QLineEdit("1.1774");
    rzEdit = new QLineEdit("-0.0290");

    //movel
    movelBtn = new QPushButton("moveL");

    //添加
    layout->addRow("ip", ipEdit);
    layout->addRow("port", portEdit);
    layout->addRow("连接状态", statusLabel);
    layout->addRow("", connectBtn);
    layout->addRow("", disConnectBtn);

    layout->addRow("关节1:", joint1Edit);
    layout->addRow("关节2:", joint2Edit);
    layout->addRow("关节3:", joint3Edit);
    layout->addRow("关节4:", joint4Edit);
    layout->addRow("关节5:", joint5Edit);
    layout->addRow("关节6:", joint6Edit);

    layout->addRow("", movejBtn);

    layout->addRow("x:", xEdit);
    layout->addRow("y:", yEdit);
    layout->addRow("z:", zEdit);
    layout->addRow("rx:", rxEdit);
    layout->addRow("ry:", ryEdit);
    layout->addRow("rz:", rzEdit);

    layout->addRow("", movelBtn);

    //设置布局
    setLayout(layout);
}

MainWindow::~MainWindow() {

}

void MainWindow::bindSignalAndSlot() {
    //连接和断开连接
    connect(connectBtn,&QPushButton::clicked,[this]{
        QString ip = ipEdit->text();
        int port = portEdit->text().toInt();
        URDriver::getInstance()->connectToRobot(ip,port);
    });
    connect(disConnectBtn,&QPushButton::clicked,[this]{
        URDriver::getInstance()->disConnectToRobot();
    });
    //movej
    connect(movejBtn,&QPushButton::clicked,this,&MainWindow::movej);
    //movel
    connect(movelBtn,&QPushButton::clicked,this,&MainWindow::movel);
}

void MainWindow::setCallBack() {
    //连接回调
    URDriver::getInstance()->setConnectCallback([this]{
        //更新界面
        this->statusLabel->setText("已连接");
    });
    URDriver::getInstance()->setDisConnectCallback([this]{
        //更新界面
        this->statusLabel->setText("断开连接");
    });
}

void MainWindow::movej() {
    //获取留个关节角度(转换弧度值)PI 180
    double joint1 = joint1Edit->text().toDouble()*DEGREEETORA;
    double joint2 = joint2Edit->text().toDouble()*DEGREEETORA;
    double joint3 = joint3Edit->text().toDouble()*DEGREEETORA;
    double joint4 = joint4Edit->text().toDouble()*DEGREEETORA;
    double joint5 = joint5Edit->text().toDouble()*DEGREEETORA;
    double joint6 = joint6Edit->text().toDouble()*DEGREEETORA;
    //保存6个关节角度
    double joints[6]{joint1,joint2,joint3,joint4,joint5,joint6};
    //movej移动
    URDriver::getInstance()->movej(joints);
}

void MainWindow::movel() {
    //位置和姿态
    double x = xEdit->text().toDouble()/1000;
    double y = yEdit->text().toDouble()/1000;
    double z = zEdit->text().toDouble()/1000;
    double rx = rxEdit->text().toDouble();
    double ry = ryEdit->text().toDouble();
    double rz = rzEdit->text().toDouble();
    //保存位置和姿态
    double pos[6]{x,y,z,rx,ry,rz};
    URDriver::getInstance()->movel(pos);
}

 

MainWindow.h代码:

//
// Created by wt on 2020/6/5.
//

#ifndef URDRIVER_MAINWINDOW_H
#define URDRIVER_MAINWINDOW_H
#include 
#include 
#include 
#include 
#include 
#include 
#include 
#include 
#include 
using namespace std;

class MainWindow: public QWidget {
private:
    //角度转弧度
    double DEGREEETORA = M_PI/180;
    //ip输入框
    QLineEdit *ipEdit;
    //端口输入框
    QLineEdit *portEdit;

    //连接状态
    QLabel *statusLabel;

    //连接机械臂按钮
    QPushButton *connectBtn;
    QPushButton *disConnectBtn;

    //movej的每一个关节输入
    QLineEdit *joint1Edit;
    QLineEdit *joint2Edit;
    QLineEdit *joint3Edit;
    QLineEdit *joint4Edit;
    QLineEdit *joint5Edit;
    QLineEdit *joint6Edit;

    //movej
    QPushButton *movejBtn;

    //movel输入
    QLineEdit *xEdit;
    QLineEdit *yEdit;
    QLineEdit *zEdit;
    QLineEdit *rxEdit;
    QLineEdit *ryEdit;
    QLineEdit *rzEdit;

    //movel
    QPushButton *movelBtn;

public:
    explicit MainWindow(QWidget* parent = Q_NULLPTR);

    ~MainWindow() override;
    //初始化ui界面
    void initUI();
    //绑定信号和槽
    void bindSignalAndSlot();
    //设置回调
    void setCallBack();
    void movej();
    //movej移动
    //movel移动
    void movel();
};


#endif //URDRIVER_MAINWINDOW_H

 

你可能感兴趣的:(qt(二))