Subscriber整合

1. 添加subscriber创建

  1. self.subscriber = self.node.create_subscription(Pose, '/turtle1/pose', self.pose_call_back,10)

2. 添加订阅回调

  1. def pose_call_back(self, pose):
  2. self.x_label.setText(str(pose.x))
  3. self.y_label.setText(str(pose.y))
  4. self.angle_label.setText(str(pose.theta))
  5. self.linear_label.setText(str(pose.linear_velocity))
  6. self.angular_label.setText(str(pose.angular_velocity))

3. 调试

t_2.png
为了能收到订阅的消息,需要定时的调用spin_once获取订阅收topic返回的消息:

  1. 定义定时器 ```python updateTimer = QTimer(self) updateTimer.setInterval(16) updateTimer.start()

updateTimer.timeout.connect(self.onUpdate)

  1. 2. 定时到之后,执行更新操作
  2. ```python
  3. def onUpdate(self):
  4. self.update()
  5. rclpy.spin_once(self.node)
  6. if not rclpy.ok():
  7. self.close()

注意: 需要调用update更新界面

完整示例代码

  1. import rclpy
  2. import sys
  3. from rclpy.node import Node
  4. from geometry_msgs.msg import Twist
  5. from turtlesim.msg import Pose
  6. from PyQt5.QtWidgets import QWidget, QApplication, QFormLayout, QLineEdit, QPushButton, QLabel
  7. from PyQt5.QtCore import QTimer
  8. class MainWindow(QWidget):
  9. def __init__(self, node):
  10. super(MainWindow, self).__init__()
  11. self.node = node
  12. # timer
  13. updateTimer = QTimer(self)
  14. updateTimer.setInterval(16)
  15. updateTimer.start()
  16. updateTimer.timeout.connect(self.onUpdate)
  17. # topic
  18. self.publisher = self.node.create_publisher(Twist, '/turtle1/cmd_vel', 10)
  19. self.subscriber = self.node.create_subscription(Pose, '/turtle1/pose', self.pose_call_back,10)
  20. self.resize(400, 120)
  21. self.setWindowTitle('小乌龟控制')
  22. # 布局
  23. layout = QFormLayout()
  24. self.setLayout(layout)
  25. # 控件
  26. self.editLinear = QLineEdit()
  27. layout.addRow("线速度", self.editLinear)
  28. self.editAngular = QLineEdit()
  29. layout.addRow("角速度", self.editAngular)
  30. # x
  31. self.x_label = QLabel('0')
  32. # y
  33. self.y_label = QLabel('0')
  34. # linear
  35. self.linear_label = QLabel('0')
  36. # angular
  37. self.angular_label = QLabel('0')
  38. # angle
  39. self.angle_label = QLabel('0')
  40. layout.addRow('x坐标', self.x_label)
  41. layout.addRow('y坐标', self.y_label)
  42. layout.addRow('线速度', self.linear_label)
  43. layout.addRow('角速度', self.angular_label)
  44. layout.addRow('角度', self.angle_label)
  45. btnSend = QPushButton("发送")
  46. layout.addRow('', btnSend)
  47. btnSend.clicked.connect(self.start_control)
  48. def start_control(self):
  49. data = Twist()
  50. data.linear.x = float(self.editLinear.text())
  51. data.angular.z = float(self.editAngular.text())
  52. self.publisher.publish(data)
  53. def pose_call_back(self, pose):
  54. self.x_label.setText(str(pose.x))
  55. self.y_label.setText(str(pose.y))
  56. self.angle_label.setText(str(pose.theta))
  57. self.linear_label.setText(str(pose.linear_velocity))
  58. self.angular_label.setText(str(pose.angular_velocity))
  59. def onUpdate(self):
  60. self.update()
  61. rclpy.spin_once(self.node)
  62. if not rclpy.ok():
  63. self.close()
  64. def main():
  65. rclpy.init()
  66. node = Node('turtlesim_control')
  67. app = QApplication(sys.argv)
  68. window = MainWindow(node)
  69. window.show()
  70. # rclpy.spin(node)
  71. result = app.exec_()
  72. node.destroy_node()
  73. rclpy.shutdown()
  74. sys.exit()
  75. if __name__ == '__main__':
  76. main()