diff --git a/robomaster_pi/conn_vel.py b/robomaster_pi/conn_vel.py index 7b54ee606fbf0c6cd56e7da32c97c916d02b1a4a..5727edea5b3b6f914a7420be254ab14b55a37be1 100644 --- a/robomaster_pi/conn_vel.py +++ b/robomaster_pi/conn_vel.py @@ -57,7 +57,7 @@ class vel_from_ros_node(Node): print("kek") - if((msg.angular.z == 0.0 and msg.linear.x == 0.0 and msg.linear.y == 0.0) or response != True): + if((msg.angular.z == 0.0 and msg.linear.x == 0.0 and msg.linear.y == 0.0) or self.response != True): self.my_ep_chassis.drive_speed(x = 0, y = 0, z = 0.5) else: self.my_ep_chassis.drive_speed(x = msg.linear.x, y = -msg.linear.y, z = -msg.angular.z * (180 / math.pi))