cut_trigger_pji.py 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239
  1. #!/usr/bin/env python
  2. # -*- coding: utf-8 -*-
  3. from __future__ import print_function
  4. import rospy
  5. import sys
  6. import math
  7. from perception_msgs.msg import PerceptionLocalization
  8. from perception_msgs.msg import PerceptionObjects
  9. from perception_msgs.msg import Object
  10. from common_msgs.msg import VehicleCmd
  11. from common_msgs.msg import Retrieval
  12. import math
  13. import rosbag
  14. import threading
  15. import time
  16. import subprocess
  17. from datetime import datetime
  18. from subprocess import Popen, PIPE
  19. import signal
  20. import os
  21. import datetime
  22. from threading import Thread
  23. from fnmatch import fnmatch
  24. from fnmatch import fnmatch, fnmatchcase
  25. from rosbag import Bag
  26. from scipy import stats
  27. obj_lock = threading.Lock()
  28. difference_lock = threading.Lock()
  29. ego_Steering_real=[]
  30. ego_throttle_real=[]
  31. ego_Brake_real=[]
  32. ego_Steering_cmd=[]
  33. ego_throttle_cmd=[]
  34. ego_Brake_cmd=[]
  35. obj_dic={}
  36. #Strg_Angle_Real_Value=0
  37. num_count_data_read=0
  38. angular_velocity_z=0
  39. num_count_pji_Control_Command=0
  40. def callback_cicv_location(data):
  41. global angular_velocity_z
  42. angular_velocity_z=data.angular_velocity_z
  43. def callback_pji_Control_Command(data):
  44. global ego_Steering_cmd
  45. global ego_throttle_cmd
  46. global num_count_pji_Control_Command
  47. num_count_pji_Control_Command+=1
  48. if num_count_pji_Control_Command == 10:
  49. ego_Steering_cmd.append(data.ICPV_Cmd_StrAngle)
  50. ego_throttle_cmd.append(data.ICPV_Cmd_AccPelPosAct)
  51. num_count_pji_Control_Command=0
  52. def callback_data_read(data):
  53. global Strg_Angle_Real_Value
  54. global ego_Steering_real
  55. global ego_throttle_real
  56. global num_count_data_read
  57. num_count_data_read+=1
  58. if num_count_data_read == 10:
  59. ego_Steering_real.append(data.ActStrWhAng)
  60. ego_throttle_real.append(data.AccPed2)
  61. num_count_data_read=0
  62. Strg_Angle_Real_Value=data.ActStrWhAng
  63. def callback_tpperception(data):
  64. global obj_dic
  65. obj_list=data.objs
  66. for obj in obj_list:
  67. if obj.x<=5 or abs(obj.y)>=10: # (obj.type !=1 and obj.type !=0 )
  68. continue
  69. #print(f"obj.type={obj.type},obj.id={obj.id},obj.x={obj.x},obj.y={obj.y}")
  70. if obj.id not in obj_dic:
  71. obj_dic[obj.id]=[]
  72. obj_dic[obj.id].append(obj.y)
  73. #print("----------------------------------------------------")
  74. def if_cutin(obj_y_list):
  75. global Strg_Angle_Real_Value
  76. global angular_velocity_z
  77. #print(obj_y_list)
  78. flag_cutin=False
  79. for i, obj_y in enumerate(obj_y_list):
  80. if abs(obj_y)>=1.1 and abs(angular_velocity_z)<=0.6:
  81. for j in range(len(obj_y_list)-i-1):
  82. if abs(obj_y_list[1+i+j])<=0.6 and abs(angular_velocity_z)<=0.6:
  83. flag_cutin=True
  84. #print('front car cut in')
  85. return flag_cutin
  86. return flag_cutin
  87. def if_cutout(obj_y_list):
  88. global Strg_Angle_Real_Value
  89. global angular_velocity_z
  90. #print(angular_velocity_z)
  91. #print(obj_y_list)
  92. #print('----------------------------------------------------------------------------')
  93. flag_cutout=False
  94. for i, obj_y in enumerate(obj_y_list):
  95. if abs(obj_y)<=0.6 and abs(angular_velocity_z)<=0.6:
  96. for j in range(len(obj_y_list)-i-1):
  97. if abs(obj_y_list[1+i+j])>=1.2 and abs(angular_velocity_z)<=0.6:
  98. flag_cutout=True
  99. #print('front car cut out')
  100. return flag_cutout
  101. return flag_cutout
  102. def if_difference(ego_Steering_real,ego_throttle_real,ego_Steering_cmd,ego_throttle_cmd): # 利用曼惠特尼U检验的方式判断车端数据和驾驶员控制数据是否存在显著差异
  103. difference_flag=False
  104. statistic_Steering, p_value_Steering = stats.mannwhitneyu(ego_Steering_real, ego_Steering_cmd)
  105. statistic_throttle, p_value_throttle = stats.mannwhitneyu(ego_throttle_real, ego_throttle_cmd)
  106. if p_value_Steering < 0.05 or p_value_throttle < 0.05:
  107. difference_flag=True
  108. return difference_flag
  109. def final_callback(event):
  110. global obj_dic
  111. global ego_Steering_real
  112. global ego_throttle_real
  113. global ego_Steering_cmd
  114. global ego_throttle_cmd
  115. cutin_flag = False
  116. cutout_flag = False
  117. flag_difference = False
  118. #print('ego_Steering_real=')
  119. #print(ego_Steering_real)
  120. #print('--------------------------------------------------------------')
  121. with obj_lock:
  122. # 先判断前车是否切入
  123. for obj_id, obj_value in obj_dic.items():
  124. if len(obj_value) <= 5:
  125. continue
  126. cutin_flag=if_cutin(obj_value)
  127. # 再判断前车是否切出
  128. for obj_id, obj_value in obj_dic.items():
  129. if len(obj_value) <= 5:
  130. continue
  131. cutout_flag=if_cutout(obj_value)
  132. with difference_lock:
  133. if cutin_flag:
  134. print('The cutting-in behavior of the front car was detected')
  135. flag_difference=if_difference(ego_Steering_real,ego_throttle_real,ego_Steering_cmd,ego_throttle_cmd)
  136. if flag_difference:
  137. event_label='cutin_difference'
  138. print('********cutin_difference********')
  139. if cutout_flag:
  140. print('The cutting-out behavior of the front car was detected')
  141. flag_difference=if_difference(ego_Steering_real,ego_throttle_real,ego_Steering_cmd,ego_throttle_cmd)
  142. if flag_difference:
  143. event_label='cutout_difference'
  144. print('********cutout_difference********')
  145. '''
  146. print('ego_Steering_real=')
  147. print(ego_Steering_real)
  148. print('--------------------------------------------------------------')
  149. print('ego_Steering_cmd=')
  150. print(ego_Steering_cmd)
  151. print('--------------------------------------------------------------')
  152. print('ego_throttle_real=')
  153. print(ego_throttle_real)
  154. print('--------------------------------------------------------------')
  155. print('ego_throttle_cmd=')
  156. print(ego_throttle_cmd)
  157. print('--------------------------------------------------------------')
  158. #print('----------------------------------------------------------------------------')
  159. '''
  160. #ego_Steering_real.clear()
  161. #ego_throttle_real.clear()
  162. #ego_Steering_cmd.clear()
  163. #ego_throttle_cmd.clear()
  164. ego_Steering_real=[1]
  165. ego_throttle_real=[1]
  166. ego_Steering_cmd=[1]
  167. ego_throttle_cmd=[1]
  168. obj_dic.clear()
  169. def listener():
  170. rospy.init_node('listener', anonymous=True)
  171. rospy.Subscriber("/cicv_location",PerceptionLocalization,callback_cicv_location) # done
  172. rospy.Subscriber("/tpperception",PerceptionObjects,callback_tpperception)
  173. rospy.Subscriber("/pj_control_pub",VehicleCmd,callback_pji_Control_Command)
  174. rospy.Subscriber("/data_read",Retrieval,callback_data_read)
  175. timer1 = rospy.Timer(rospy.Duration(3.5), final_callback)
  176. rospy.spin()
  177. if __name__ == '__main__':
  178. listener()