diff --git a/robomaster_pi/conn_vel.py b/robomaster_pi/conn_vel.py
index 4412f0f790f151918c2a0a9931251de959e6116c..b405625fc565c39303878f43b00ec59c09ce1762 100644
--- a/robomaster_pi/conn_vel.py
+++ b/robomaster_pi/conn_vel.py
@@ -67,7 +67,7 @@ class vel_from_ros_node(Node):
     def pose_callback(self, msg: Twist):
         
         
-        if((msg.angular.z == 0.0 and msg.linear.x == 0.0 and msg.linear.y == 0.0) or self.response != 0):
+        if((msg.angular.z == 0.0 and msg.linear.x == 0.0 and msg.linear.y == 0.0)):
             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))