autoware_msgs.go 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477
  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 AdjustXY struct {
  9. msg.Package `ros:"autoware_msgs"`
  10. Header std_msgs.Header `rosname:"header"`
  11. X int32 `rosname:"x"`
  12. Y int32 `rosname:"y"`
  13. }
  14. type AutowareCentroids struct {
  15. msg.Package `ros:"autoware_msgs"`
  16. Header std_msgs.Header `rosname:"header"`
  17. Points []geometry_msgs.Point `rosname:"points"`
  18. }
  19. type AutowareCloudCluster struct {
  20. msg.Package `ros:"autoware_msgs"`
  21. Id uint32 `rosname:"id"`
  22. Label string `rosname:"label"`
  23. Score float64 `rosname:"score"`
  24. Cloud sensor_msgs.PointCloud2 `rosname:"cloud"`
  25. MinPoint geometry_msgs.PointStamped `rosname:"min_point"`
  26. MaxPoint geometry_msgs.PointStamped `rosname:"max_point"`
  27. AvgPoint geometry_msgs.PointStamped `rosname:"avg_point"`
  28. CentroidPoint geometry_msgs.PointStamped `rosname:"centroid_point"`
  29. EstimatedAngle float64 `rosname:"estimated_angle"`
  30. Dimensions geometry_msgs.Vector3 `rosname:"dimensions"`
  31. EigenValues geometry_msgs.Vector3 `rosname:"eigen_values"`
  32. EigenVectors []geometry_msgs.Vector3 `rosname:"eigen_vectors"`
  33. FpfhDescriptor std_msgs.Float32MultiArray `rosname:"fpfh_descriptor"`
  34. BoundingBox BoundingBox `rosname:"bounding_box"`
  35. ConvexHull geometry_msgs.PolygonStamped `rosname:"convex_hull"`
  36. IndicatorState uint32 `rosname:"indicator_state"`
  37. }
  38. type AutowareCloudClusterArray struct {
  39. msg.Package `ros:"autoware_msgs"`
  40. Header std_msgs.Header `rosname:"header"`
  41. Clusters []AutowareCloudCluster `rosname:"clusters"`
  42. }
  43. type ValueSet struct {
  44. msg.Package `ros:"autoware_msgs"`
  45. Center int32 `rosname:"center"`
  46. Range int32 `rosname:"range"`
  47. }
  48. type ColorSet struct {
  49. msg.Package `ros:"autoware_msgs"`
  50. Hue int32 `rosname:"Hue"`
  51. Sat int32 `rosname:"Sat"`
  52. Val int32 `rosname:"Val"`
  53. }
  54. type AutowareControlCommand struct {
  55. msg.Package `ros:"autoware_msgs"`
  56. LinearVelocity int32 `rosname:"linear_velocity"`
  57. LinearAcceleration int32 `rosname:"linear_acceleration"`
  58. SteeringAngle int32 `rosname:"steering_angle"`
  59. }
  60. type AutowareControlCommandStamped struct {
  61. msg.Package `ros:"autoware_msgs"`
  62. Cmd AutowareControlCommand `rosname:"cmd"`
  63. }
  64. type AutowareDTLane struct {
  65. msg.Package `ros:"autoware_msgs"`
  66. Dist float64 `rosname:"dist"`
  67. Dir float64 `rosname:"dir"`
  68. Apara float64 `rosname:"apara"`
  69. R float64 `rosname:"r"`
  70. Slope float64 `rosname:"slope"`
  71. Cant float64 `rosname:"cant"`
  72. Lw float64 `rosname:"lw"`
  73. Rw float64 `rosname:"rw"`
  74. }
  75. type AutowareWaypointState struct {
  76. msg.Package `ros:"autoware_msgs"`
  77. Aid int32 `rosname:"aid"`
  78. NullState uint8 `rosname:"NULLSTATE"`
  79. LaneChangeState uint8 `rosname:"lanechange_state"`
  80. SteeringState uint8 `rosname:"steering_state"`
  81. StrLeft uint8 `rosname:"STR_LEFT"`
  82. StrRight uint8 `rosname:"STR_RIGHT"`
  83. StrStraight uint8 `rosname:"STR_STRAIGHT"`
  84. StrBack uint8 `rosname:"STR_BACK"`
  85. AccelState uint8 `rosname:"accel_state"`
  86. StopState uint8 `rosname:"stop_state"`
  87. TypeStopLine uint8 `rosname:"TYPE_STOPLINE"`
  88. TypeStop uint8 `rosname:"TYPE_STOP"`
  89. EventState uint8 `rosname:"event_state"`
  90. TypeEventNull uint8 `rosname:"TYPE_EVENT_NULL"`
  91. TypeEventGoal uint8 `rosname:"TYPE_EVENT_GOAL"`
  92. TypeEventMiddleGoal uint8 `rosname:"TYPE_EVENT_MIDDLE_GOAL"`
  93. TypeEventPositionStop uint8 `rosname:"TYPE_EVENT_POSITION_STOP"`
  94. TypeEventBusStop uint8 `rosname:"TYPE_EVENT_BUS_STOP"`
  95. TypeEventParking uint8 `rosname:"TYPE_EVENT_PARKING"`
  96. }
  97. type AutowareWaypoint struct {
  98. msg.Package `ros:"autoware_msgs"`
  99. Gid int32 `rosname:"gid"`
  100. Lid int32 `rosname:"lid"`
  101. Pose geometry_msgs.PoseStamped `rosname:"pose"`
  102. Twist geometry_msgs.TwistStamped `rosname:"twist"`
  103. DTLane AutowareDTLane `rosname:"dtlane"`
  104. ChangeFlag int32 `rosname:"change_flag"`
  105. WpState AutowareWaypointState `rosname:"wpstate"`
  106. LaneId uint32 `rosname:"lane_id"`
  107. LeftLaneId uint32 `rosname:"left_lane_id"`
  108. RightLaneId uint32 `rosname:"right_lane_id"`
  109. StopLineId uint32 `rosname:"stop_line_id"`
  110. Cost float32 `rosname:"cost"`
  111. TimeCost float32 `rosname:"time_cost"`
  112. Direction uint32 `rosname:"direction"`
  113. }
  114. type AutowareLane struct {
  115. msg.Package `ros:"autoware_msgs"`
  116. Header std_msgs.Header `rosname:"header"`
  117. Increment int32 `rosname:"increment"`
  118. LaneId int32 `rosname:"lane_id"`
  119. Waypoints []AutowareWaypoint `rosname:"waypoints"`
  120. LaneIndex uint32 `rosname:"lane_index"`
  121. Cost float32 `rosname:"cost"`
  122. ClosestObjectDistance float32 `rosname:"closest_object_distance"`
  123. ClosestObjectVelocity float32 `rosname:"closest_object_velocity"`
  124. IsBlocked bool `rosname:"is_blocked"`
  125. }
  126. type AutowareLaneArray struct {
  127. msg.Package `ros:"autoware_msgs"`
  128. Id int32 `rosname:"id"`
  129. Lanes []AutowareLane `rosname:"lanes"`
  130. }
  131. type AutowareDetectedObject struct {
  132. msg.Package `ros:"autoware_msgs"`
  133. Id uint32 `rosname:"id"`
  134. Label string `rosname:"label"`
  135. Score float32 `rosname:"score"`
  136. Color std_msgs.ColorRGBA `rosname:"color"`
  137. Valid bool `rosname:"valid"`
  138. String string `rosname:"space_frame"`
  139. Pose geometry_msgs.Pose `rosname:"pose"`
  140. Dimensions geometry_msgs.Vector3 `rosname:"dimensions"`
  141. Variance geometry_msgs.Vector3 `rosname:"variance"`
  142. Velocity geometry_msgs.Twist `rosname:"velocity"`
  143. Acceleration geometry_msgs.Twist `rosname:"acceleration"`
  144. PointCloud sensor_msgs.PointCloud2 `rosname:"pointcloud"`
  145. ConvexHull geometry_msgs.PolygonStamped `rosname:"convex_hull"`
  146. CandidateTrajectories AutowareLaneArray `rosname:"candidate_trajectories"`
  147. PoseReliable bool `rosname:"pose_reliable"`
  148. VelocityReliable bool `rosname:"velocity_reliable"`
  149. AccelerationReliable bool `rosname:"acceleration_reliable"`
  150. ImageFrame string `rosname:"image_frame"`
  151. X int32 `rosname:"x"`
  152. Y int32 `rosname:"y"`
  153. Width int32 `rosname:"width"`
  154. Height int32 `rosname:"height"`
  155. Angle float32 `rosname:"angle"`
  156. RoiImage sensor_msgs.Image `rosname:"roi_image"`
  157. IndicatorState uint8 `rosname:"indicator_state"`
  158. BehaviorState uint8 `rosname:"behavior_state"`
  159. UserDefinedInfo []string `rosname:"user_defined_info"`
  160. }
  161. type AutowareDetectedObjectArray struct {
  162. msg.Package `ros:"autoware_msgs"`
  163. Header std_msgs.Header `rosname:"header"`
  164. Objects []AutowareDetectedObject `rosname:"objects"`
  165. }
  166. type ExtractedPosition struct {
  167. msg.Package `ros:"autoware_msgs"`
  168. SignalId int32 `rosname:"signalId"`
  169. U int32 `rosname:"u"`
  170. V int32 `rosname:"v"`
  171. Radius int32 `rosname:"radius"`
  172. X float64 `rosname:"x"`
  173. Y float64 `rosname:"y"`
  174. Z float64 `rosname:"z"`
  175. Hang float64 `rosname:"hang"`
  176. Type int8 `rosname:"type"`
  177. LinkId int32 `rosname:"linkId"`
  178. PlId int32 `rosname:"plId"`
  179. }
  180. type GeometricRectangle struct {
  181. msg.Package `ros:"autoware_msgs"`
  182. Wl float32 `rosname:"wl"`
  183. Wr float32 `rosname:"wr"`
  184. Lf float32 `rosname:"lf"`
  185. Lb float32 `rosname:"lb"`
  186. }
  187. type ICPStat struct {
  188. msg.Package `ros:"autoware_msgs"`
  189. Header std_msgs.Header `rosname:"header"`
  190. ExeTime float32 `rosname:"exe_time"`
  191. Score float32 `rosname:"score"`
  192. Velocity float32 `rosname:"velocity"`
  193. Acceleration float32 `rosname:"acceleration"`
  194. UsePredictPose int32 `rosname:"use_predict_pose"`
  195. }
  196. type ImageLaneObjects struct {
  197. msg.Package `ros:"autoware_msgs"`
  198. Header std_msgs.Header `rosname:"header"`
  199. LaneLX1 int32 `rosname:"lane_l_x1"`
  200. LaneLY1 int32 `rosname:"lane_l_y1"`
  201. LaneLX2 int32 `rosname:"lane_l_x2"`
  202. LaneLY2 int32 `rosname:"lane_l_y2"`
  203. LaneRX1 int32 `rosname:"lane_r_x1"`
  204. LaneRY1 int32 `rosname:"lane_r_y1"`
  205. LaneRX2 int32 `rosname:"lane_r_x2"`
  206. LaneRY2 int32 `rosname:"lane_r_y2"`
  207. }
  208. type ImageRect struct {
  209. msg.Package `ros:"autoware_msgs"`
  210. X int32 `rosname:"x"`
  211. Y int32 `rosname:"y"`
  212. Height int32 `rosname:"height"`
  213. Width int32 `rosname:"width"`
  214. Score float32 `rosname:"score"`
  215. }
  216. type ImageObj struct {
  217. msg.Package `ros:"autoware_msgs"`
  218. Header std_msgs.Header `rosname:"header"`
  219. Type string `rosname:"type"`
  220. Obj []ImageRect `rosname:"obj"`
  221. }
  222. type ImageObjects struct {
  223. msg.Package `ros:"autoware_msgs"`
  224. Header std_msgs.Header `rosname:"header"`
  225. CarNum uint8 `rosname:"car_num"`
  226. CarType []int32 `rosname:"car_type"`
  227. Score []float32 `rosname:"score"`
  228. CornerPoint []int32 `rosname:"corner_point"`
  229. }
  230. type ImageRectRanged struct {
  231. msg.Package `ros:"autoware_msgs"`
  232. Rect ImageRect `rosname:"rect"`
  233. Range float32 `rosname:"range"`
  234. MinHeight float32 `rosname:"min_height"`
  235. MaxHeight float32 `rosname:"max_height"`
  236. }
  237. type ImageObjRanged struct {
  238. msg.Package `ros:"autoware_msgs"`
  239. Header std_msgs.Header `rosname:"header"`
  240. Type string `rosname:"type"`
  241. Obj []ImageRectRanged `rosname:"obj"`
  242. }
  243. type ImageObjTracked struct {
  244. msg.Package `ros:"autoware_msgs"`
  245. Header std_msgs.Header `rosname:"header"`
  246. Type string `rosname:"type"`
  247. TotalNum uint8 `rosname:"total_num"`
  248. ObjId []int32 `rosname:"obj_id"`
  249. RectRanged []ImageRectRanged `rosname:"rect_ranged"`
  250. RealData []int32 `rosname:"real_data"`
  251. Lifespan []int32 `rosname:"lifespan"`
  252. }
  253. type IndicatorCmd struct {
  254. msg.Package `ros:"autoware_msgs"`
  255. Header std_msgs.Header `rosname:"header"`
  256. L int32 `rosname:"l"`
  257. R int32 `rosname:"r"`
  258. }
  259. type NDTStat struct {
  260. msg.Package `ros:"autoware_msgs"`
  261. Header std_msgs.Header `rosname:"header"`
  262. ExeTime float32 `rosname:"exe_time"`
  263. Iteration int32 `rosname:"iteration"`
  264. Score float32 `rosname:"score"`
  265. Velocity float32 `rosname:"velocity"`
  266. Acceleration float32 `rosname:"acceleration"`
  267. UsePredictPose int32 `rosname:"use_predict_pose"`
  268. }
  269. type ObjLabel struct {
  270. msg.Package `ros:"autoware_msgs"`
  271. Header std_msgs.Header `rosname:"header"`
  272. Type string `rosname:"type"`
  273. ObjId []int32 `rosname:"obj_id"`
  274. ReprojectedPos []geometry_msgs.Point `rosname:"reprojected_pos"`
  275. }
  276. type ObjPose struct {
  277. msg.Package `ros:"autoware_msgs"`
  278. Header std_msgs.Header `rosname:"header"`
  279. Type string `rosname:"type"`
  280. ObjId []int32 `rosname:"obj_id"`
  281. Obj []geometry_msgs.PoseArray `rosname:"obj"`
  282. }
  283. type PointsImage struct {
  284. msg.Package `ros:"autoware_msgs"`
  285. Header std_msgs.Header `rosname:"header"`
  286. Distance []float32 `rosname:"distance"`
  287. Intensity []float32 `rosname:"intensity"`
  288. MinHeight []float32 `rosname:"min_height"`
  289. MaxHeight []float32 `rosname:"max_height"`
  290. MaxY int32 `rosname:"max_y"`
  291. MinY int32 `rosname:"min_y"`
  292. ImageHeight int32 `rosname:"image_height"`
  293. ImageWidth int32 `rosname:"image_width"`
  294. }
  295. type ProjectionMatrix struct {
  296. msg.Package `ros:"autoware_msgs"`
  297. Header std_msgs.Header `rosname:"header"`
  298. ProjectionMatrix [16]float64 `rosname:"projection_matrix"`
  299. }
  300. type SteerCmd struct {
  301. msg.Package `ros:"autoware_msgs"`
  302. Header std_msgs.Header `rosname:"header"`
  303. Steer int32 `rosname:"steer"`
  304. }
  305. type AccelCmd struct {
  306. msg.Package `ros:"autoware_msgs"`
  307. Header std_msgs.Header `rosname:"header"`
  308. Accel int32 `rosname:"accel"`
  309. }
  310. type BrakeCmd struct {
  311. msg.Package `ros:"autoware_msgs"`
  312. Header std_msgs.Header `rosname:"header"`
  313. Brake int32 `rosname:"brake"`
  314. }
  315. type LampCmd struct {
  316. msg.Package `ros:"autoware_msgs"`
  317. Header std_msgs.Header `rosname:"header"`
  318. L int32 `rosname:"l"`
  319. R int32 `rosname:"r"`
  320. }
  321. type Gear struct {
  322. msg.Package `ros:"autoware_msgs"`
  323. None uint8 `rosname:"NONE"`
  324. Park uint8 `rosname:"PARK"`
  325. Reverse uint8 `rosname:"REVERSE"`
  326. Neutral uint8 `rosname:"NEUTRAL"`
  327. Drive uint8 `rosname:"DRIVE"`
  328. Low uint8 `rosname:"LOW"`
  329. Gear uint8 `rosname:"gear"`
  330. }
  331. type AutoWareVehicleCmd struct {
  332. msg.Package `ros:"autoware_msgs"`
  333. Header std_msgs.Header `rosname:"header"`
  334. SteerCmd SteerCmd `rosname:"steer_cmd"`
  335. AccelCmd AccelCmd `rosname:"accel_cmd"`
  336. BrakeCmd BrakeCmd `rosname:"brake_cmd"`
  337. LampCmd LampCmd `rosname:"lamp_cmd"`
  338. GearCmd Gear `rosname:"gear_cmd"`
  339. mode int32 `rosname:"mode"`
  340. TwistCmd geometry_msgs.TwistStamped `rosname:"twist_cmd"`
  341. CtrlCmd AutowareControlCommand `rosname:"ctrl_cmd"`
  342. Emergency int32 `rosname:"emergency"`
  343. }
  344. type RemoteCmd struct {
  345. msg.Package `ros:"autoware_msgs"`
  346. Header std_msgs.Header `rosname:"header"`
  347. VehicleCmd AutoWareVehicleCmd `rosname:"vehicle_cmd"`
  348. ControlMode int32 `rosname:"control_mode"`
  349. }
  350. type ScanImage struct {
  351. msg.Package `ros:"autoware_msgs"`
  352. Header std_msgs.Header `rosname:"header"`
  353. Distance []float32 `rosname:"distance"`
  354. Intensity []float32 `rosname:"intensity"`
  355. MaxY int32 `rosname:"max_y"`
  356. MinY int32 `rosname:"min_y"`
  357. }
  358. type Signals struct {
  359. msg.Package `ros:"autoware_msgs"`
  360. Header std_msgs.Header `rosname:"header"`
  361. Signals []ExtractedPosition `rosname:"Signals"`
  362. }
  363. type State struct {
  364. msg.Package `ros:"autoware_msgs"`
  365. Header std_msgs.Header `rosname:"header"`
  366. VehicleState string `rosname:"vehicle_state"`
  367. MissionState string `rosname:"mission_state"`
  368. BehaviorState string `rosname:"behavior_state"`
  369. MotionState string `rosname:"motion_state"`
  370. }
  371. type StateCmd struct {
  372. msg.Package `ros:"autoware_msgs"`
  373. Header std_msgs.Header `rosname:"header"`
  374. Cmd int32 `rosname:"cmd"`
  375. }
  376. type SyncTimeDiff struct {
  377. msg.Package `ros:"autoware_msgs"`
  378. Header std_msgs.Header `rosname:"header"`
  379. TimeDiff float64 `rosname:"time_diff"`
  380. Camera std_msgs.Time `rosname:"camera"`
  381. Lidar std_msgs.Time `rosname:"lidar"`
  382. }
  383. type SyncTimeMonitor struct {
  384. msg.Package `ros:"autoware_msgs"`
  385. Header std_msgs.Header `rosname:"header"`
  386. ImageRaw float64 `rosname:"image_raw"`
  387. PointsRaw float64 `rosname:"points_raw"`
  388. PointsImage float64 `rosname:"points_image"`
  389. VscanPoints float64 `rosname:"vscan_points"`
  390. VscanImage float64 `rosname:"vscan_image"`
  391. ImageObj float64 `rosname:"image_obj"`
  392. ImageObjRanged float64 `rosname:"image_obj_ranged"`
  393. ImageObjTracked float64 `rosname:"image_obj_tracked"`
  394. CurrentPose float64 `rosname:"current_pose"`
  395. ObjLabel float64 `rosname:"obj_label"`
  396. ClusterCentroids float64 `rosname:"cluster_centroids"`
  397. ObjPose float64 `rosname:"obj_pose"`
  398. ExecutionTime float64 `rosname:"execution_time"`
  399. CycleTime float64 `rosname:"cycle_time"`
  400. TimeDiff float64 `rosname:"time_diff"`
  401. }
  402. type TrafficLight struct {
  403. msg.Package `ros:"autoware_msgs"`
  404. Header std_msgs.Header
  405. TrafficLight int32
  406. }
  407. type TrafficLightResult struct {
  408. msg.Package `ros:"autoware_msgs"`
  409. Header std_msgs.Header
  410. LightId int32
  411. RecognitionResult int32
  412. RecognitionResultStr string
  413. LaneId int32
  414. }
  415. type TrafficLightResultArray struct {
  416. msg.Package `ros:"autoware_msgs"`
  417. Header std_msgs.Header
  418. Results []TrafficLightResult
  419. }
  420. type TunedResult struct {
  421. msg.Package `ros:"autoware_msgs"`
  422. Header std_msgs.Header
  423. Red ColorSet `rosname:"Red"`
  424. Yellow ColorSet `rosname:"Yellow"`
  425. Green ColorSet `rosname:"Green"`
  426. }
  427. type VehicleLocation struct {
  428. msg.Package `ros:"autoware_msgs"`
  429. Header std_msgs.Header
  430. LaneArrayId int32
  431. WaypointIndex int32
  432. }
  433. type VehicleStatus struct {
  434. msg.Package `ros:"autoware_msgs"`
  435. msg.Definitions `ros:"int32 MODE_MANUAL=0,int32 MODE_AUTO=1,int32 LAMP_LEFT=1,int32 LAMP_RIGHT=2,int32 LAMP_HAZARD=3"`
  436. Header std_msgs.Header
  437. Tm string
  438. Drivemode int32
  439. Steeringmode int32
  440. CurrentGear Gear
  441. Speed float64
  442. Drivepedal int32
  443. Brakepedal int32
  444. Angle float64
  445. Lamp int32
  446. Light int32
  447. }
  448. type VscanTracked struct {
  449. msg.Package `ros:"autoware_msgs"`
  450. Position geometry_msgs.Point
  451. Orientation float32
  452. Velocity float32
  453. GeoRect GeometricRectangle
  454. }
  455. type VscanTrackedArray struct {
  456. msg.Package `ros:"autoware_msgs"`
  457. Header std_msgs.Header
  458. ObjTracked []VscanTracked
  459. }