turtlebot3-burger_150.png
turtlebot3-waffle-pi_150.png
turtlebot3-arm_150.png
walking-y2_150.png
turbot3-multi_150.png
turbot3-dl-ros1_150.png
turbot3-ai.png
turbot3-dl-ros2_150.png
turbot3-slam_150.png
turbot3-arm_150.png
turtlebot4-lite_150.png
turtlebot4-pro_150.png
turbot4-dl_150.png
turbot4-ai_150.png
aidriving-racebot_150.png
aidriving-autodrive_150.png
turtlebot-arm_150.png
openmanipulator-x_150.png
Home » ROS与QT语言入门教程 » ROS与QT语言入门教程-按钮控制小乌龟运动

ROS与QT语言入门教程-按钮控制小乌龟运动

纠错,疑问,交流: 请进入讨论区请点击进入页面,扫码加入微信群或Q群进行交流

获取最新文章: 扫一扫加入“创客智造”公众号

ROS与QT语言入门教程-按钮控制小乌龟运动

说明

  • 在ROS QT GUI模板的基础上,实现使用按钮控制小海龟运动,向前,向后,向左,向右

点击查看完整代码

ui界面

  • main_window.ui文件:拖入四个按钮控件,将对象名分别改为up,down,left、right 请输入图片描述

编写节点 **qnode.hpp**头文件

public:
//void run();
  void up();
  void down(); 
  void left(); 
  void right();

代码解释:

  • 注释掉run()函数,声明小海龟向前up()函数,向后down()函数,向左left()函数,向右right()函数

**qnode.cpp**源文件

#include <geometry_msgs/Twist.h>  

namespace qtros{
    bool QNode::init() 
    {
        chatter_publisher = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 1000);
    }

    bool QNode::init(const std::string &master_url, const std::string &host_url) 
    {
        chatter_publisher = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 1000);
    }
}
void QNode::up()
{
  ros::Rate loop_rate(1);

  if(ros::ok())
  {
    geometry_msgs::Twist msg;
    msg.linear.x = 1.0;
    msg.angular.z = 0.0;

    chatter_publisher.publish(msg);

    ros::spinOnce();
    loop_rate.sleep();
  }
  log(Info,std::string("up"));
}

void QNode::down()
{
  ros::Rate loop_rate(1);

  if(ros::ok())
  {
    geometry_msgs::Twist msg;
    msg.linear.x = -1.0;
    msg.angular.z = 0.0;

    chatter_publisher.publish(msg);

    ros::spinOnce();
    loop_rate.sleep();
  }
  log(Info,std::string("down"));
}

void QNode::left()
{
  ros::Rate loop_rate(1);

  if(ros::ok())
  {
    geometry_msgs::Twist msg;
    msg.linear.x = 0.0;
    msg.angular.z = 1.0;

    chatter_publisher.publish(msg);

    ros::spinOnce();
    loop_rate.sleep();
  }
  log(Info,std::string("left"));
}

void QNode::right()
{
  ros::Rate loop_rate(1);

  if(ros::ok())
  {
    geometry_msgs::Twist msg;
   msg.linear.x = 0.0;
    msg.angular.z = -1.0;

    chatter_publisher.publish(msg);

    ros::spinOnce();
    loop_rate.sleep();
  }
  log(Info,std::string("right"));
}

代码解释:

  • 修改发布者订阅的话题,/turtle1/cmd_vel
  • 定义小海龟向前,向后,向左,向右的函数
  • 修改msg.linear.x和msg.angular.z的值,改变小海龟运动的方向和速度
  • 注释掉void QNode::run()函数

编写主窗口 main_window.hpp头文件

public Q_SLOTS:
    void on_up_clicked();
    void on_down_clicked(); 
    void on_left_clicked(); 
    void on_right_clicked();  

代码解释:

  • 主窗口下,声明四个按键的槽函数

main_window.cpp源文件

void tortoise::MainWindow::on_up_clicked()
{
  qnode.up();
}

void tortoise::MainWindow::on_down_clicked()
{
  qnode.down();
}

void tortoise::MainWindow::on_left_clicked()
{
  qnode.left();
}

void tortoise::MainWindow::on_right_clicked()
{
  qnode.right();
}

代码解释:

  • 定义四个按键的槽函数,并且让它调用qnode对应的函数,让小海龟运动

编译运行:

  • 启动ros master
$ roscore

  • 启动小海龟节点
$ rosrun turtlesim turtlesim_nodes

  • 运行qt程序

  • 点击up、down、left、right按钮,小海龟向前、向后、向左、向右

请输入图片描述

参考资料

纠错,疑问,交流: 请进入讨论区请点击进入页面,扫码加入微信群或Q群进行交流

获取最新文章: 扫一扫加入“创客智造”公众号


标签: ros与qt语言入门教程, ros qt