common_msgs.go 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254
  1. package pjisuv_msgs
  2. import (
  3. "github.com/bluenviron/goroslib/v2/pkg/msg"
  4. "github.com/bluenviron/goroslib/v2/pkg/msgs/geometry_msgs"
  5. "github.com/bluenviron/goroslib/v2/pkg/msgs/sensor_msgs"
  6. "github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
  7. )
  8. type Header struct {
  9. msg.Package `ros:"common_msgs"`
  10. SequenceNum int32 `rosname:"sequence_num"`
  11. TimeStamp float64 `rosname:"time_stamp"`
  12. ModuleName string `rosname:"module_name"`
  13. Version string `rosname:"version"`
  14. FaultVec FaultVec `rosname:"fault_vec"`
  15. TimeStatistics TimeStatistics `rosname:"time_statistics"`
  16. }
  17. type FaultVec struct {
  18. msg.Package `ros:"common_msgs"`
  19. InfoVec []FaultInfo `rosname:"info_vec"`
  20. ModuleFaultLevel int32 `rosname:"module_fault_level"`
  21. }
  22. type TimeStatistics struct {
  23. msg.Package `ros:"common_msgs"`
  24. DevTimeStatusMsg []TimeStatus `rosname:"dev_time_status_msg"`
  25. SendingTimestamp float64 `rosname:"sending_timestamp"`
  26. }
  27. type FaultInfo struct {
  28. msg.Package `ros:"common_msgs"`
  29. TimestampSec float64 `rosname:"timestamp_sec"`
  30. ModuleName string `rosname:"module_name"`
  31. Version string `rosname:"version"`
  32. ErrorCode int32 `rosname:"error_code"`
  33. Msg string `rosname:"msg"`
  34. FaultLevel int8 `rosname:"fault_level"`
  35. FaultType int8 `rosname:"fault_type"`
  36. }
  37. type TimeStatus struct {
  38. msg.Package `ros:"common_msgs"`
  39. Dtime float64 `rosname:"dtime"`
  40. SourceNodeName string `rosname:"source_node_name"`
  41. DestinationNodeName string `rosname:"destination_node_name"`
  42. }
  43. type Retrieval struct {
  44. msg.Package `ros:"common_msgs"`
  45. Header std_msgs.Header `rosname:"header"`
  46. AsVehAccelerationValue float64 `rosname:"AS_Veh_Acceleration_Value"` // 惯导采集到的加速度
  47. AsDriverTakeoverReq int16 `rosname:"AS_Driver_TakeOver_Req"` // 驾驶员接管提醒(2B9)
  48. VcuAccelPosValue float64 `rosname:"VCU_Accel_Pos_Value"` // 实际加速踏板位置
  49. VcuBrkPelPosValue float64 `rosname:"VCU_BrkPel_Pos_Value"` // 实际制动踏板位置
  50. VcuRealSpeed float64 `rosname:"VCU_Real_Speed"` // 当前车速
  51. VcuCurrentGear int16 `rosname:"VCU_Current_Gear"` // 当前档位
  52. VcuParkingSt int16 `rosname:"VCU_Parking_St"` // 当前P档位
  53. AutoDLimitInReason int16 `rosname:"AutoD_Limitin_Reason"` // 限制进入自动驾驶原因
  54. EmergencyStopReason int16 `rosname:"Emergency_Stop_Reason"` // 紧急停车激活原因
  55. VcuDriverTakeoverReq int16 `rosname:"VCU_Driver_TakeOver_Req"` // 驾驶员接管提醒(2BA)
  56. VcuVehicleDriveModeSt int16 `rosname:"VCU_Vehicle_Drive_Mode_St"` // 车辆驾驶模式
  57. AutoDOutReason int16 `rosname:"AutoD_Out_Reason"` // 退出自动驾驶原因
  58. BrakeSysFaultSt int16 `rosname:"Brak_Sys_Fault_St"` // 制动系统故障
  59. StrgAngleRealValue float64 `rosname:"Strg_Angle_Real_Value"` // 方向盘实际转角
  60. StrgAngleSpdValue float64 `rosname:"Strg_Angle_Spd_Value"` // 方向盘当前实际速度反馈
  61. StrgWorkmodeSt int16 `rosname:"Strg_WorkMode_St"` // 当前系统实际工作模式
  62. BCHornSt int16 `rosname:"BC_Horn_St"` // 喇叭状态
  63. }
  64. type CicvMovingObject__ struct {
  65. msg.Package `ros:"common_msgs"`
  66. Header std_msgs.Header
  67. Id uint32
  68. Label string
  69. Probability float32
  70. LabelProbability float32
  71. MotionStatus uint32
  72. Ttc float32
  73. Variance float32
  74. DataSource string
  75. LeftTopX float32
  76. LeftTopY float32
  77. RightTopX float32
  78. RightTopY float32
  79. LeftButtomX float32
  80. LeftButtomY float32
  81. RightButtomX float32
  82. RightButtomY float32
  83. MinZ float32
  84. MaxZ float32
  85. Pose geometry_msgs.Pose
  86. Dimensions geometry_msgs.Vector3
  87. Velocity geometry_msgs.Twist
  88. Acceleration geometry_msgs.Twist
  89. ConvexHull geometry_msgs.PolygonStamped
  90. Speed float32
  91. SpeedDirection float32
  92. GlobalX float32
  93. GlobalY float32
  94. Lane int32
  95. RelativeLane int32
  96. GlobalLane int32
  97. }
  98. type CommonCicvMovingObject struct {
  99. msg.Package `ros:"common_msgs"`
  100. Header std_msgs.Header
  101. Id uint32
  102. Label string
  103. Probability float32
  104. LabelProbability float32
  105. MotionStatus uint32
  106. Ttc float32
  107. Variance float32
  108. DataSource string
  109. X1 float32
  110. Y1 float32
  111. X2 float32
  112. Y2 float32
  113. X3 float32
  114. Y3 float32
  115. X4 float32
  116. Y4 float32
  117. MinZ float32
  118. MaxZ float32
  119. Pose geometry_msgs.Pose
  120. Dimensions geometry_msgs.Vector3
  121. Velocity geometry_msgs.Twist
  122. Acceleration geometry_msgs.Twist
  123. ConvexHull geometry_msgs.PolygonStamped
  124. Speed float32
  125. SpeedDirection float32
  126. GlobalX float32
  127. GlobalY float32
  128. Lane int32
  129. RelativeLane int32
  130. GlobalLane int32
  131. ClusterPoints sensor_msgs.PointCloud2
  132. }
  133. type CommonCicvMovingObjects struct {
  134. msg.Package `ros:"common_msgs"`
  135. Header std_msgs.Header
  136. Num int32
  137. Objects []CommonCicvMovingObject
  138. }
  139. type Vector3WithCovariance struct {
  140. msg.Package `ros:"common_msgs"`
  141. X UnsureVar
  142. Y UnsureVar
  143. Z UnsureVar
  144. }
  145. type PoseEuler struct {
  146. msg.Package `ros:"common_msgs"`
  147. Position Vector3WithCovariance
  148. Rotation EulerWithCovariance
  149. }
  150. type DRPoseWithTime struct {
  151. msg.Package `ros:"common_msgs"`
  152. Week int32
  153. Utctime float64
  154. DrTime float64
  155. PoseEuler PoseEuler
  156. }
  157. type UnsureVar struct {
  158. msg.Package `ros:"common_msgs"`
  159. Variable float64
  160. VarStd float64
  161. }
  162. type EulerWithCovariance struct {
  163. msg.Package `ros:"common_msgs"`
  164. Roll UnsureVar
  165. Pitch UnsureVar
  166. Yaw UnsureVar
  167. }
  168. type LLH struct {
  169. msg.Package `ros:"common_msgs"`
  170. Lat UnsureVar
  171. Lon UnsureVar
  172. Height UnsureVar
  173. }
  174. type NavStatus struct {
  175. msg.Package `ros:"common_msgs"`
  176. UtcTime float64
  177. GpsStatus int8
  178. PosStatus int32
  179. AttStatus int32
  180. InitStatus int32
  181. SateNum int32
  182. Hdop float32
  183. Pdop float32
  184. DiffAge float32
  185. }
  186. type Pose struct {
  187. msg.Package `ros:"common_msgs"`
  188. PoseEuler PoseEuler
  189. PoseQuaternion PoseQuaternion
  190. Status int8
  191. }
  192. type Quaternion struct {
  193. msg.Package `ros:"common_msgs"`
  194. X float64
  195. Y float64
  196. Z float64
  197. W float64
  198. }
  199. type Vector3 struct {
  200. msg.Package `ros:"common_msgs"`
  201. X float64
  202. Y float64
  203. Z float64
  204. }
  205. type PoseQuaternion struct {
  206. msg.Package `ros:"common_msgs"`
  207. Position Vector3WithCovariance
  208. Quaternion Quaternion
  209. RpyCovariance Vector3
  210. }
  211. type Twist struct {
  212. msg.Package `ros:"common_msgs"`
  213. Velocity Vector3WithCovariance
  214. AngularVelocity Vector3WithCovariance
  215. }
  216. type CommonVehicleCmd struct {
  217. msg.Package `ros:"common_msgs"`
  218. Header std_msgs.Header
  219. ICPVCmdStrAngle float64 `rosname:"ICPV_Cmd_StrAngle"`
  220. ICPVCmdStrAngleLimit float64 `rosname:"ICPV_Cmd_StrAngleLimit"`
  221. ICPVCmdEPSXBWEn float64 `rosname:"ICPV_Cmd_EPSXBW_En"`
  222. ICPVCmdEPSDir float64 `rosname:"ICPV_Cmd_EPSDir"`
  223. ICPVCmdStrAngleSpd float64 `rosname:"ICPV_Cmd_StrAngleSpd"`
  224. ICPVCmdChecksum float64 `rosname:"ICPV_Cmd_Checksum"`
  225. ICPVCmdRCnt float64 `rosname:"ICPV_Cmd_RCnt"`
  226. ICPVCmdTgtSft float64 `rosname:"ICPV_Cmd_TgtSft"`
  227. ICPVCmdAccPelEnable float64 `rosname:"ICPV_Cmd_AccPelEnable"`
  228. ICPVCmdBrkPelEnable float64 `rosname:"ICPV_Cmd_BrkPelEnable"`
  229. ICPVCmdAccPelPosAct float64 `rosname:"ICPV_Cmd_AccPelPosAct"`
  230. ICPVCmdAccPelPosActInv float64 `rosname:"ICPV_Cmd_AccPelPosActInv"`
  231. ICPVCmdBrkPelPosAct float64 `rosname:"ICPV_Cmd_BrkPelPosAct"`
  232. ICPVCmdBrkPelPosActInv float64 `rosname:"ICPV_Cmd_BrkPelPosActInv"`
  233. ICPVCmdBrkLightReq float64 `rosname:"ICPV_Cmd_BrkLightReq"`
  234. ICPVCmdTgtSftEnable float64 `rosname:"ICPV_Cmd_TgtSftEnable"`
  235. ICPVCmdATOModeEnable float64 `rosname:"ICPV_Cmd_ATOModeEnable"`
  236. CANICPVVCUControlEPBREQ float64 `rosname:"CAN_ICPV_VCU_Control_EPB_REQ"`
  237. CANICPVVCUBUZZING float64 `rosname:"CAN_ICPV_VCU_BUZZING"`
  238. TargetX float64
  239. TargetY float64
  240. Velocity float64
  241. CalcAccel float64
  242. AutoMode int16
  243. }