#!/usr/bin/env python3
#coding=utf-8
from PyQt5.QtWidgets import *
import sys
from window import MainWindow,TurtleWindow
import rospy
if __name__ =='__main__':
rospy.init_node('turtle_ctrl_node')
app=QApplication(sys.argv)
#窗口展示
window=TurtleWindow()
window.show()
sys.exit(app.exec_())
#!/usr/bin/env python3
#coding=utf-8
from PyQt5.QtWidgets import *
from PyQt5.QtCore import *
from PyQt5.QtGui import *
import sys
import rospy
#geometry_msgs/Twist
from geometry_msgs.msg import Twist
#turtlesim/Pose
from turtlesim.msg import Pose
class MainWindow(QWidget):
def __init__(self):
super(MainWindow,self).__init__()
self.setWindowTitle('小乌龟控制')
self.resize(400,0)
#布局
layout=QFormLayout()
self.setLayout(layout)
#输入框
self.le_linear=QLineEdit()
self.le_angular=QLineEdit()
#发送
btn=QPushButton('发送')
layout.addRow('线速度',self.le_linear)
layout.addRow('角速度',self.le_angular)
layout.addRow(btn)
#事件
btn.clicked.connect(self.click_send)
topic_name='/turtle1/cmd_vel'
self.publisher=rospy.Publisher(topic_name,Twist,queue_size=10)
def click_send(self):
linaer=float(self.le_linear.text())
angular=float(self.le_angular.text())
twist=Twist()
#线速度
twist.linear.x=linaer
#角速度
twist.angular.z=angular
self.publisher.publish(twist)
class TurtleWindow(QWidget):
def __init__(self, parent=None):
super(TurtleWindow,self).__init__(parent)
#创建自己的刷新定时器
update_timer=QTimer(self)
#设置定时器频率
update_timer.setInterval(20)
update_timer.start()
#监听定时器
update_timer.timeout.connect(self.on_update)
self.setWindowTitle('小乌龟控制')
self.resize(400,0)
#布局
layout=QFormLayout()
self.setLayout(layout)
#输入框
self.le_linear=QLineEdit()
self.le_angular=QLineEdit()
#显示文本
self.lb_x=QLabel()
self.lb_y=QLabel()
self.lb_linear=QLabel()
self.lb_angular=QLabel()
self.lb_theta=QLabel()
#发送
btn=QPushButton('发送')
layout.addRow('线速度',self.le_linear)
layout.addRow('角速度',self.le_angular)
layout.addRow('当前x坐标',self.lb_x)
layout.addRow('当前y坐标',self.lb_y)
layout.addRow('当前线速度',self.lb_linear)
layout.addRow('当前角速度',self.lb_angular)
layout.addRow('当前角度',self.lb_theta)
layout.addRow(btn)
#事件
btn.clicked.connect(self.click_send)
topic_name='/turtle1/cmd_vel'
self.publisher=rospy.Publisher(topic_name,Twist,queue_size=10)
#订阅小乌龟的位置
pose_topic_name='/turtle1/pose'
rospy.Subscriber(pose_topic_name,Pose,self.pose_callback)
def click_send(self):
linaer=float(self.le_linear.text())
angular=float(self.le_angular.text())
twist=Twist()
#线速度
twist.linear.x=linaer
#角速度
twist.angular.z=angular
self.publisher.publish(twist)
def pose_callback(self,msg):
#赋值操作
self.lb_x.setText(str(msg.x))
self.lb_y.setText(str(msg.y))
self.lb_linear.setText(str(msg.linear_velocity))
self.lb_angular.setText(str(msg.angular_velocity))
self.lb_theta.setText(str(msg.theta))
def on_update(self):
#手动渲染ui
self.update()
if rospy.is_shutdown():
#关闭了
self.close()