XTDrone/control/yolo_human_tracking.py

86 lines
3.1 KiB
Python
Raw Permalink Normal View History

2020-03-23 16:09:44 +08:00
import rospy
2020-07-17 19:24:18 +08:00
from geometry_msgs.msg import Twist, PoseStamped
2020-05-20 13:30:28 +08:00
from std_msgs.msg import String
2020-03-23 16:09:44 +08:00
import sys
sys.path.append('/home/robin/catkin_ws/devel/lib/python2.7/dist-packages')
2020-11-04 22:39:42 +08:00
from pyquaternion import Quaternion
2020-03-23 16:09:44 +08:00
from darknet_ros_msgs.msg import BoundingBoxes
import time
import math
2020-05-20 13:30:28 +08:00
2020-03-23 16:09:44 +08:00
def darknet_callback(data):
2021-02-09 23:51:44 +08:00
global find_cnt, twist, cmd, target_height_mask, target_height,theta, get_time
2020-03-23 16:09:44 +08:00
for target in data.bounding_boxes:
if(target.id==0):
2020-05-20 13:30:28 +08:00
print('find human')
2020-11-26 12:18:55 +08:00
z = height / math.sin(theta)
2020-07-23 10:06:27 +08:00
u = (target.xmax+target.xmin)/2
v = (target.ymax+target.ymin)/2
u_ = u-u_center
v_ = v-v_center
u_velocity = -Kp_xy*u_
v_velocity = -Kp_xy*v_
2020-11-26 12:18:55 +08:00
x_velocity = v_velocity*z/(v_*math.cos(theta)+fy*math.sin(theta))
y_velocity = (z*u_velocity-u_*math.cos(theta)*x_velocity)/fx
2020-07-23 10:06:27 +08:00
twist.linear.x = x_velocity
twist.linear.y = y_velocity
2020-07-17 19:24:18 +08:00
twist.linear.z = Kp_z*(target_height-height)
2020-05-20 13:30:28 +08:00
cmd = ''
2021-02-09 23:51:44 +08:00
find_cnt = find_cnt + 1
get_time = False
2020-07-17 19:24:18 +08:00
def local_pose_callback(data):
2020-07-22 20:37:08 +08:00
global height, target_height, target_set
height = data.pose.position.z
if not target_set:
target_height = height
target_set = True
2020-11-04 22:39:42 +08:00
def cam_pose_callback(data):
global theta
q = Quaternion(data.pose.orientation.w, data.pose.orientation.x, data.pose.orientation.y, data.pose.orientation.z)
theta = q.yaw_pitch_roll[1]
2020-05-20 13:30:28 +08:00
2020-07-17 19:24:18 +08:00
if __name__ == "__main__":
height = 0
2020-07-22 20:37:08 +08:00
target_height = 0
target_set = False
2021-02-09 23:51:44 +08:00
find_cnt = 0
find_cnt_last = 0
2020-11-25 21:18:06 +08:00
not_find_time = 0
get_time = False
2020-05-20 13:30:28 +08:00
twist = Twist()
cmd = String()
2020-11-26 12:18:55 +08:00
theta = 0
2020-10-16 00:34:13 +08:00
u_center=640/2
v_center=360/2
fx = 205.46963709898583
fy = 205.46963709898583
2020-11-25 21:18:06 +08:00
Kp_xy = 0.5
2020-07-17 19:24:18 +08:00
Kp_z = 1
2020-05-20 13:30:28 +08:00
vehicle_type = sys.argv[1]
2020-07-17 19:24:18 +08:00
vehicle_id = sys.argv[2]
2020-05-20 13:30:28 +08:00
rospy.init_node('yolo_human_tracking')
2020-12-31 21:03:41 +08:00
rospy.Subscriber("/uav_"+vehicle_id+"/darknet_ros/bounding_boxes", BoundingBoxes, darknet_callback)
2020-07-17 19:24:18 +08:00
rospy.Subscriber(vehicle_type+'_'+vehicle_id+"/mavros/local_position/pose", PoseStamped, local_pose_callback)
2020-11-04 22:39:42 +08:00
rospy.Subscriber('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cam_pose', PoseStamped, cam_pose_callback)
2021-04-03 21:34:19 +08:00
cmd_vel_pub = rospy.Publisher('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cmd_vel_flu', Twist, queue_size=2)
2020-07-17 19:24:18 +08:00
cmd_pub = rospy.Publisher('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cmd', String, queue_size=2)
2020-05-20 13:30:28 +08:00
rate = rospy.Rate(60)
2021-04-03 21:34:19 +08:00
while not rospy.is_shutdown():
2020-05-20 13:30:28 +08:00
rate.sleep()
2021-04-03 21:34:19 +08:00
cmd_vel_pub.publish(twist)
2020-05-20 13:30:28 +08:00
cmd_pub.publish(cmd)
2021-02-09 23:51:44 +08:00
if find_cnt - find_cnt_last == 0:
2020-11-25 21:18:06 +08:00
if not get_time:
not_find_time = rospy.get_time()
get_time = True
if rospy.get_time() - not_find_time > 2.0:
twist.linear.x = 0.0
twist.linear.y = 0.0
twist.linear.z = 0.0
cmd = 'HOVER'
print(cmd)
get_time = False
2021-02-09 23:51:44 +08:00
find_cnt_last = find_cnt