< >
Home » ROS与Qt5人机交互 » ROS与Qt5人机交互界面开发-实现控制机器人速度与方向

ROS与Qt5人机交互界面开发-实现控制机器人速度与方向

ROS与Qt5人机交互界面开发-实现控制机器人速度与方向

说明:

  • 介绍如何实现控制机器人速度与方向

步骤:

  • 我这里主要就是参考teleop_twist_keyboard项目的源代码,移植到自己程序
  • 首先在ui界面添加按钮(注意按钮上显示的文字):

请输入图片描述

  • 同时在ui界面设置每个按钮的shortcut,就能实现键盘控制:
    请输入图片描述

  • 关联这些按钮的点击事件到同一槽函数

//绑定速度控制按钮
connect(ui.pushButton_i,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_u,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_o,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_j,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_l,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_m,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_back,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_backr,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
  • 槽函数:
//速度控制相关按钮处理槽函数
void MainWindow::slot_cmd_control()
{

    QPushButton* btn=qobject_cast<QPushButton*>(sender());
    char key=btn->text().toStdString()[0];
    //速度
    float liner=ui.horizontalSlider_linear->value()*0.01;
    float turn=ui.horizontalSlider_raw->value()*0.01;
    bool is_all=ui.checkBox_use_all->isChecked();
    switch (key) {
        case 'u':
            qnode.move_base(is_all?'U':'u',liner,turn);
        break;
        case 'i':
            qnode.move_base(is_all?'I':'i',liner,turn);
        break;
        case 'o':
            qnode.move_base(is_all?'O':'o',liner,turn);
        break;
        case 'j':
            qnode.move_base(is_all?'J':'j',liner,turn);
        break;
        case 'l':
            qnode.move_base(is_all?'L':'l',liner,turn);
        break;
        case 'm':
            qnode.move_base(is_all?'M':'m',liner,turn);
        break;
        case ',':
            qnode.move_base(is_all?'<':',',liner,turn);
        break;
        case '.':
            qnode.move_base(is_all?'>':'.',liner,turn);
        break;
    }
}
  • 创建发布者:
//速度控制话题
cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
  • qnode.move_base实现:
//发布机器人速度控制
 void QNode::move_base(char k,float speed_linear,float speed_trun)
 {
     std::map<char, std::vector<float>> moveBindings
     {
       {'i', {1, 0, 0, 0}},
       {'o', {1, 0, 0, -1}},
       {'j', {0, 0, 0, 1}},
       {'l', {0, 0, 0, -1}},
       {'u', {1, 0, 0, 1}},
       {',', {-1, 0, 0, 0}},
       {'.', {-1, 0, 0, 1}},
       {'m', {-1, 0, 0, -1}},
       {'O', {1, -1, 0, 0}},
       {'I', {1, 0, 0, 0}},
       {'J', {0, 1, 0, 0}},
       {'L', {0, -1, 0, 0}},
       {'U', {1, 1, 0, 0}},
       {'<', {-1, 0, 0, 0}},
       {'>', {-1, -1, 0, 0}},
       {'M', {-1, 1, 0, 0}},
       {'t', {0, 0, 1, 0}},
       {'b', {0, 0, -1, 0}},
       {'k', {0, 0, 0, 0}},
       {'K', {0, 0, 0, 0}}
     };
     char key=k;
     //计算是往哪个方向
     float x = moveBindings[key][0];
     float y = moveBindings[key][1];
     float z = moveBindings[key][2];
     float th = moveBindings[key][3];
     //计算线速度和角速度
     float speed = speed_linear;
     float turn = speed_trun;
     // Update the Twist message
     geometry_msgs::Twist twist;
    twist.linear.x = x * speed;
    twist.linear.y = y * speed;
    twist.linear.z = z * speed;

    twist.angular.x = 0;
    twist.angular.y = 0;
    twist.angular.z = th * turn;

    // Publish it and resolve any remaining callbacks
    cmd_pub.publish(twist);
    ros::spinOnce();

 }

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros与qt5人机交互界面开发