perception_msgs.go 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430
  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 PerceptionObjects struct {
  9. msg.Package `ros:"perception_msgs"`
  10. Header Header `rosname:"header"`
  11. Objs []PerceptionObject `rosname:"objs"`
  12. Cells []ObstacleCell `rosname:"cells"`
  13. }
  14. type PerceptionObject struct {
  15. msg.Package `ros:"perception_msgs"`
  16. Id uint32 `rosname:"id"`
  17. X float32 `rosname:"x"`
  18. Y float32 `rosname:"y"`
  19. Z float32 `rosname:"z"`
  20. Vxrel float32 `rosname:"vxrel"`
  21. Vyrel float32 `rosname:"vyrel"`
  22. Xabs float64 `rosname:"xabs"`
  23. Yabs float64 `rosname:"yabs"`
  24. Vxabs float32 `rosname:"vxabs"`
  25. Vyabs float32 `rosname:"vyabs"`
  26. Width float32 `rosname:"width"`
  27. Length float32 `rosname:"length"`
  28. Height float32 `rosname:"height"`
  29. Speed float32 `rosname:"speed"`
  30. Heading float32 `rosname:"heading"`
  31. Type uint8 `rosname:"type"`
  32. Source uint8 `rosname:"source"`
  33. Confidence float32 `rosname:"confidence"`
  34. Age uint32 `rosname:"age"`
  35. Velocitystatus uint8 `rosname:"velocitystatus"`
  36. Cells []ObstacleCell `rosname:"cells"`
  37. }
  38. type ObstacleCell struct {
  39. msg.Package `ros:"perception_msgs"`
  40. Idc int32 `rosname:"idc"`
  41. X float64 `rosname:"x"`
  42. Y float64 `rosname:"y"`
  43. Xg float64 `rosname:"xg"`
  44. Yg float64 `rosname:"yg"`
  45. }
  46. type PerceptionLocalization struct {
  47. msg.Package `ros:"perception_msgs"`
  48. Header std_msgs.Header `rosname:"header"`
  49. FrameUnmber uint64 `rosname:"frame_unmber"`
  50. FusionLevel int8 `rosname:"fusion_level"`
  51. Status int8 `rosname:"status"`
  52. Roll float64 `rosname:"roll"`
  53. Pitch float64 `rosname:"pitch"`
  54. Yaw float64 `rosname:"yaw"`
  55. RollStd float32 `rosname:"roll_std"`
  56. PitchStd float32 `rosname:"pitch_std"`
  57. YawStd float32 `rosname:"yaw_std"`
  58. Qw float64 `rosname:"qw"`
  59. Qx float64 `rosname:"qx"`
  60. Qy float64 `rosname:"qy"`
  61. Qz float64 `rosname:"qz"`
  62. AngularVelocityX float64 `rosname:"angular_velocity_x"`
  63. AngularVelocityY float64 `rosname:"angular_velocity_y"`
  64. AngularVelocityZ float64 `rosname:"angular_velocity_z"`
  65. Latitude float64 `rosname:"latitude"`
  66. Longitude float64 `rosname:"longitude"`
  67. Altitude float64 `rosname:"altitude"`
  68. LatitudeStd float32 `rosname:"latitude_std"`
  69. LongitudeStd float32 `rosname:"longitude_std"`
  70. AltitudeStd float32 `rosname:"altitude_std"`
  71. PositionX float64 `rosname:"position_x"`
  72. PositionY float64 `rosname:"position_y"`
  73. PositionZ float64 `rosname:"position_z"`
  74. PositionXStd float32 `rosname:"position_x_std"`
  75. PositionYStd float32 `rosname:"position_y_std"`
  76. PositionZStd float32 `rosname:"position_z_std"`
  77. VelocityX float64 `rosname:"velocity_x"`
  78. VelocityY float64 `rosname:"velocity_y"`
  79. VelocityZ float64 `rosname:"velocity_z"`
  80. VelocityXStd float32 `rosname:"velocity_x_std"`
  81. VelocityYStd float32 `rosname:"velocity_y_std"`
  82. VelocityZStd float32 `rosname:"velocity_z_std"`
  83. VelocityRx float64 `rosname:"velocity_rx"`
  84. VelocityRy float64 `rosname:"velocity_ry"`
  85. VelocityRz float64 `rosname:"velocity_rz"`
  86. VelocityRxStd float32 `rosname:"velocity_rx_std"`
  87. VelocityRyStd float32 `rosname:"velocity_ry_std"`
  88. VelocityRzStd float32 `rosname:"velocity_rz_std"`
  89. AccelX float64 `rosname:"accel_x"`
  90. AccelY float64 `rosname:"accel_y"`
  91. AccelZ float64 `rosname:"accel_z"`
  92. }
  93. type CameraObject struct {
  94. msg.Package `ros:"perception_msgs"`
  95. Header std_msgs.Header
  96. SensorId uint8
  97. ObjectId uint32
  98. DetectConfidence float32
  99. TypeConfidence float32
  100. Azimuth float32
  101. Yaw float32
  102. Type uint8
  103. TrackingTime float32
  104. TrackingLevel int8
  105. LaneAssignment int8
  106. Position geometry_msgs.Point32
  107. Velocity geometry_msgs.Vector3
  108. Acceleration geometry_msgs.Vector3
  109. Dimensions geometry_msgs.Vector3
  110. PixelCentralPoint Point2D
  111. PixelBoxSize Point2D
  112. }
  113. type CameraObjectList struct {
  114. msg.Package `ros:"perception_msgs"`
  115. Header std_msgs.Header
  116. FrameNumber uint64
  117. SensorSource int8
  118. Cameraobjects []CameraObject
  119. }
  120. type CameraTrafficLight struct {
  121. msg.Package `ros:"perception_msgs"`
  122. Header std_msgs.Header
  123. SensorId int8
  124. ObjectId int32
  125. DetectConfidence float32
  126. TypeConfidence float32
  127. Position geometry_msgs.Point32
  128. PixelCentralPoint Point2D
  129. PixelBoxSize Point2D
  130. LightColor uint8
  131. LightShape uint8
  132. }
  133. type CameraTrafficLightList struct {
  134. msg.Package `ros:"perception_msgs"`
  135. Header std_msgs.Header
  136. FrameId uint64
  137. SensorSource int8
  138. Cameratrafficlights []CameraTrafficLight
  139. }
  140. type CameraTrafficSign struct {
  141. msg.Package `ros:"perception_msgs"`
  142. Header std_msgs.Header
  143. SensorId int8
  144. ObjectId int32
  145. DetectConfidence float32
  146. TypeConfidence float32
  147. Position geometry_msgs.Point32
  148. PixelCentralPoint Point2D
  149. PixelBoxSize Point2D
  150. Type int32
  151. }
  152. type CameraTrafficSignList struct {
  153. msg.Package `ros:"perception_msgs"`
  154. Header std_msgs.Header
  155. FrameNumber uint64
  156. SensorSource int8
  157. Cameratrafficsigns []CameraTrafficSign
  158. }
  159. type PerceptionCentroids struct {
  160. msg.Package `ros:"perception_msgs"`
  161. Header std_msgs.Header
  162. Points []geometry_msgs.Point
  163. }
  164. type PerceptionCicvMovingObject struct {
  165. msg.Package `ros:"perception_msgs"`
  166. Header std_msgs.Header
  167. Id uint32
  168. Label string
  169. Probability float32
  170. LabelProbability float32
  171. MotionStatus uint32
  172. Color std_msgs.ColorRGBA
  173. Ttc float32
  174. Variance float32
  175. DataSource string
  176. Valid bool
  177. X1 float32
  178. Y1 float32
  179. X2 float32
  180. Y2 float32
  181. X3 float32
  182. Y3 float32
  183. X4 float32
  184. Y4 float32
  185. MinZ float32
  186. MaxZ float32
  187. Pose geometry_msgs.Pose
  188. Dimensions geometry_msgs.Vector3
  189. Velocity geometry_msgs.Twist
  190. Acceleration geometry_msgs.Twist
  191. VelocityReliable bool
  192. PoseReliable bool
  193. AccelerationReliable bool
  194. IsStatic bool
  195. CornerIndex int32
  196. ConvexHull geometry_msgs.PolygonStamped
  197. Cells []ObstacleCell
  198. Speed float32
  199. SpeedDirection float32
  200. GlobalX float32
  201. GlobalY float32
  202. Lane int32
  203. X int32
  204. Y int32
  205. Width int32
  206. Height int32
  207. Angle float32
  208. RelativeLane int32
  209. GlobalLane int32
  210. ClusterPoints sensor_msgs.PointCloud2
  211. BehaviorState uint8
  212. }
  213. type PerceptionCicvMovingObjects struct {
  214. msg.Package `ros:"perception_msgs"`
  215. Header std_msgs.Header
  216. Num int32
  217. Objects []PerceptionCicvMovingObject
  218. }
  219. type CtrlTest struct {
  220. msg.Package `ros:"perception_msgs"`
  221. Header std_msgs.Header
  222. ICPVCmdStrAngle float64 `rosname:"ICPV_Cmd_StrAngle"`
  223. ICPVCmdStrAngleLimit float64 `rosname:"ICPV_Cmd_StrAngleLimit"`
  224. ICPVCmdEPSXBWEn float64 `rosname:"ICPV_Cmd_EPSXBW_En"`
  225. ICPVCmdEPSDir float64 `rosname:"ICPV_Cmd_EPSDir"`
  226. ICPVCmdStrAngleSpd float64 `rosname:"ICPV_Cmd_StrAngleSpd"`
  227. ICPVCmdAccPelPosAct float64 `rosname:"ICPV_Cmd_AccPelPosAct"`
  228. ICPVCmdAccPelPosActInv float64 `rosname:"ICPV_Cmd_AccPelPosActInv"`
  229. ICPVCmdBrkPelPosAct float64 `rosname:"ICPV_Cmd_BrkPelPosAct"`
  230. ICPVCmdBrkPelPosActInv float64 `rosname:"ICPV_Cmd_BrkPelPosActInv"`
  231. ICPVCmdBrkPelEnable float64 `rosname:"ICPV_Cmd_BrkPelEnable"`
  232. ICPVCmdAccPelEnable float64 `rosname:"ICPV_Cmd_AccPelEnable"`
  233. ICPVCmdBrakeLightReq float64 `rosname:"ICPV_Cmd_BrakeLightReq"`
  234. ICPVCmdTgtSft float64 `rosname:"ICPV_Cmd_TgtSft"`
  235. ICPVCmdTgtSftEnable float64 `rosname:"ICPV_Cmd_TgtSftEnable"`
  236. ICPVCmdATOModEnable float64 `rosname:"ICPV_Cmd_ATOModEnable"`
  237. VCU1ICPVEPSDir float64 `rosname:"VCU1_ICPV_EPSDir"`
  238. VCU1ICPVStrAngle float64 `rosname:"VCU1_ICPV_StrAngle"`
  239. VCU1ICPVStrAngleSpd float64 `rosname:"VCU1_ICPV_StrAngleSpd"`
  240. VCU1ICPVStrAngleFb float64 `rosname:"VCU1_ICPV_StrAngleFb"`
  241. VCU1ICPVEPSMODE float64 `rosname:"VCU1_ICPV_EPSMODE"`
  242. VCU1ICPVStrAngleSpdDir float64 `rosname:"VCU1_ICPV_StrAngleSpdDir"`
  243. VCU1ICPVYawRate float64 `rosname:"VCU1_ICPV_YawRate"`
  244. VCU1ICPVLongAcc float64 `rosname:"VCU1_ICPV_LongAcc"`
  245. PCUICPVTMDirSts float64 `rosname:"PCU_ICPV_TMDirSts"`
  246. VCU1ICPVESCWhlRRSpd float64 `rosname:"VCU1_ICPV_ESCWhlRRSpd"`
  247. VCU1ICPVESCWhlRLSpd float64 `rosname:"VCU1_ICPV_ESCWhlRLSpd"`
  248. VCU1ICPVESCWhlFRSpd float64 `rosname:"VCU1_ICPV_ESCWhlFRSpd"`
  249. VCU1ICPVESCWhlFLSpd float64 `rosname:"VCU1_ICPV_ESCWhlFLSpd"`
  250. VCU1ICPVVehSpd float64 `rosname:"VCU1_ICPV_VehSpd"`
  251. VCUIPCVBrkLgtSts float64 `rosname:"VCU_IPCV_BrkLgtSts"`
  252. VUCICPVAccPed float64 `rosname:"VUC_ICPV_AccPed"`
  253. VUCICPVBrkPed float64 `rosname:"VUC_ICPV_BrkPed"`
  254. VCUICPVAccPelPosFb float64 `rosname:"VCU_ICPV_AccPelPosFb"`
  255. VCUICPVBrkPelPosFb float64 `rosname:"VCU_ICPV_BrkPelPosFb"`
  256. VCUICPVTgtSftFb float64 `rosname:"VCU_ICPV_TgtSftFb"`
  257. VCUICPVAccPelSta float64 `rosname:"VCU_ICPV_AccPelSta"`
  258. VCUICPVBrkPelSta float64 `rosname:"VCU_ICPV_BrkPelSta"`
  259. VCUICPVATOModFb float64 `rosname:"VCU_ICPV_ATOModFb"`
  260. VCUICPVVCUSta float64 `rosname:"VCU_ICPV_VCUSta"`
  261. VCUICPVCruiseControlSts float64 `rosname:"VCU_ICPV_CruiseControlSts"`
  262. VCUICPVCruiseSwitchSts float64 `rosname:"VCU_ICPV_CruiseSwitchSts"`
  263. VCUICPVEPBSysVCU float64 `rosname:"VCU_ICPV_EPBSysVCU"`
  264. VCUICPVVCUGearLevPos float64 `rosname:"VCU_ICPV_VCUGearLevPos"`
  265. VCU1ICPVBackDoorSts float64 `rosname:"VCU1_ICPV_BackDoorSts"`
  266. TargetYaw float64
  267. TargetVel float64
  268. TargetX float64
  269. TargetY float64
  270. TargetTime float64
  271. }
  272. type GpsPosition struct {
  273. msg.Package `ros:"perception_msgs"`
  274. Header std_msgs.Header
  275. PlatId int32
  276. ErrorCode int32
  277. GpsFlag int32
  278. PositionStatus int32 `rosname:"positionStatus"`
  279. GpsWeek uint32
  280. GpsMillisecond uint32
  281. Longitude float64
  282. Latitude float64
  283. Height float64
  284. GaussX int32 `rosname:"gaussX"`
  285. GaussY int32 `rosname:"gaussY"`
  286. Pitch int32
  287. Roll int32
  288. Azimuth int32
  289. NorthVelocity int32 `rosname:"northVelocity"`
  290. EastVelocity int32 `rosname:"eastVelocity"`
  291. UpVelocity int32 `rosname:"upVelocity"`
  292. GpsConfidence int32
  293. }
  294. type PerceptionLidarObject struct {
  295. msg.Package `ros:"perception_msgs"`
  296. Header std_msgs.Header
  297. ObjectId uint32
  298. Type uint8
  299. DetectConfidence float32
  300. TypeConfidence float32
  301. Dimensions geometry_msgs.Vector3
  302. ClusterPose geometry_msgs.Pose
  303. TrackedPose geometry_msgs.Pose
  304. ClusterYaw float32
  305. TrackedYaw float32
  306. Azimuth float32
  307. Velocity geometry_msgs.Vector3
  308. Acceleration geometry_msgs.Vector3
  309. TrackingState uint8
  310. Cells []ObstacleCell
  311. }
  312. type LidarObjectList struct {
  313. msg.Package `ros:"perception_msgs"`
  314. Header std_msgs.Header
  315. FrameNumber uint64
  316. SensorSource uint8
  317. Lidarobjects []PerceptionLidarObject
  318. Cells []ObstacleCell
  319. }
  320. type Point2D struct {
  321. msg.Package `ros:"perception_msgs"`
  322. X float64
  323. Y float64
  324. }
  325. type Point64 struct {
  326. msg.Package `ros:"perception_msgs"`
  327. X float64
  328. Y float64
  329. Z float64
  330. }
  331. type Polygonbus struct {
  332. msg.Package `ros:"perception_msgs"`
  333. Points []Point64
  334. }
  335. type PolygonStamped struct {
  336. msg.Package `ros:"perception_msgs"`
  337. Header std_msgs.Header
  338. Polygon Polygonbus
  339. }
  340. type RadarObject struct {
  341. msg.Package `ros:"perception_msgs"`
  342. Header std_msgs.Header
  343. IsInvalid bool
  344. IsMatched bool
  345. IsStill bool
  346. ClusterMask uint8
  347. RadarId uint8
  348. ObjectId uint16
  349. Type uint8
  350. LifeCount uint16
  351. Rcs float32
  352. Confidence float32
  353. Azimuth float32
  354. Position geometry_msgs.Point32
  355. Velocity geometry_msgs.Vector3
  356. Acceleration geometry_msgs.Vector3
  357. Dimensions geometry_msgs.Vector3
  358. }
  359. type RadarObjectList struct {
  360. msg.Package `ros:"perception_msgs"`
  361. Header std_msgs.Header
  362. Radarobjects []RadarObject
  363. }
  364. type SingleTrafficLight struct {
  365. msg.Package `ros:"perception_msgs"`
  366. Color int8
  367. Id string
  368. Confidence float32
  369. TrackingTime float32
  370. Shape int8
  371. }
  372. type TrafficLightDetection struct {
  373. msg.Package `ros:"perception_msgs"`
  374. Header Header
  375. TrafficLight []SingleTrafficLight
  376. ContainLights bool
  377. }
  378. type Trajectory struct {
  379. msg.Package `ros:"perception_msgs"`
  380. Header std_msgs.Header
  381. FrameNumber uint64
  382. IsValidFrame bool
  383. Trajectoryinfo TrajectoryInfo
  384. }
  385. type TrajectoryInfo struct {
  386. msg.Package `ros:"perception_msgs"`
  387. PathId int32
  388. TotalPathLength float32
  389. TotalPathTime float32
  390. DecisionType int8
  391. LightType int8
  392. LaneIds []string
  393. Trajectorypoints []TrajectoryPoint
  394. }
  395. type TrajectoryPoint struct {
  396. msg.Package `ros:"perception_msgs"`
  397. Position Point2D
  398. Velocity float32
  399. Heading float32
  400. Curvature float32
  401. S float32
  402. T float32
  403. A float32
  404. PointType int8
  405. }
  406. type UltraCell struct {
  407. msg.Package `ros:"perception_msgs"`
  408. Id int32
  409. DirectDist float32
  410. IndirectDist float32
  411. Status int32
  412. }
  413. type UltrasonicParking struct {
  414. msg.Package `ros:"perception_msgs"`
  415. Header std_msgs.Header
  416. Cell []UltraCell
  417. }