XTDrone/control/rover_self_driving.py

34 lines
929 B
Python
Raw Normal View History

2020-05-14 12:50:41 +08:00
import rospy
from geometry_msgs.msg import Twist
from std_msgs.msg import Int16
Kp = 0.003
2020-12-14 19:22:34 +08:00
Vx = 5
2020-05-14 12:50:41 +08:00
def lane_mid_error_callback(msg):
global twist
2020-05-15 11:27:11 +08:00
if msg.data == 1000:
2020-05-14 12:50:41 +08:00
twist.linear.x = 0.0
2020-05-15 11:27:11 +08:00
twist.linear.y = 0.0
else:
if abs(msg.data) > 20:
2020-05-20 13:30:28 +08:00
twist.linear.y = - Kp * msg.data
2020-05-15 11:27:11 +08:00
else:
2020-05-20 13:30:28 +08:00
twist.linear.y = 0.0
2020-12-14 19:22:34 +08:00
twist.linear.x = Vx * (1 - abs(twist.linear.y))
2020-05-14 12:50:41 +08:00
if __name__ == "__main__":
rospy.init_node('rover_self_driving')
cmd_vel_flu_pub = rospy.Publisher('/xtdrone/rover_0/cmd_vel_flu', Twist, queue_size=2)
lane_mid_error_sub = rospy.Subscriber("/rover_0/lane_mid_error",Int16,callback=lane_mid_error_callback)
twist = Twist()
rate = rospy.Rate(50)
while not rospy.is_shutdown():
cmd_vel_flu_pub.publish(twist)
rate.sleep()