custom_msgs.go 9.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270
  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 Can struct {
  9. msg.Package `ros:"common_msgs"`
  10. Header std_msgs.Header
  11. CanId uint32
  12. Remoteflag uint8
  13. Externflag uint8
  14. Datalen uint8
  15. Data [8]uint8
  16. }
  17. type CustomControlCommand struct {
  18. msg.Package `ros:"common_msgs"`
  19. LinearVelocity float64
  20. LinearAcceleration float64
  21. SteeringAngle float64
  22. }
  23. type CustomControlCommandStamped struct {
  24. msg.Package `ros:"common_msgs"`
  25. Header std_msgs.Header
  26. Cmd CustomControlCommand
  27. }
  28. type CpsCmd struct {
  29. msg.Package `ros:"common_msgs"`
  30. Header std_msgs.Header
  31. CpsOffset int16
  32. CpsTimestamp uint16
  33. }
  34. type CustomDetectedObject struct {
  35. msg.Package `ros:"common_msgs"`
  36. Header std_msgs.Header
  37. Id uint32
  38. Label string
  39. Score float32
  40. Color std_msgs.ColorRGBA
  41. Valid bool
  42. SpaceFrame string
  43. Pose geometry_msgs.Pose
  44. Dimensions geometry_msgs.Vector3
  45. Variance geometry_msgs.Vector3
  46. Velocity geometry_msgs.Twist
  47. Acceleration geometry_msgs.Twist
  48. Pointcloud sensor_msgs.PointCloud2
  49. ConvexHull geometry_msgs.PolygonStamped
  50. CandidateTrajectories CustomLaneArray
  51. PoseReliable bool
  52. VelocityReliable bool
  53. AccelerationReliable bool
  54. IsStatic bool
  55. CornerIndex int32
  56. ImageFrame string
  57. X int32
  58. Y int32
  59. Width int32
  60. Height int32
  61. Angle float32
  62. RoiImage sensor_msgs.Image
  63. IndicatorState uint8
  64. BehaviorState uint8
  65. UserDefinedInfo []string
  66. }
  67. type CustomDetectedObjectArray struct {
  68. msg.Package `ros:"common_msgs"`
  69. Header std_msgs.Header
  70. Objects []CustomDetectedObject
  71. }
  72. type CustomDTLane struct {
  73. msg.Package `ros:"common_msgs"`
  74. Dist float64
  75. Dir float64
  76. Apara float64
  77. R float64
  78. Slope float64
  79. Cant float64
  80. Lw float64
  81. Rw float64
  82. }
  83. type GpsAndImu struct {
  84. msg.Package `ros:"common_msgs"`
  85. Gps sensor_msgs.NavSatFix
  86. Imu sensor_msgs.Imu
  87. }
  88. type GuiCtrl struct {
  89. msg.Package `ros:"common_msgs"`
  90. Header std_msgs.Header
  91. StartFlag uint8
  92. SpeedEnable uint8
  93. TargetSpeed float32
  94. MapPath string
  95. }
  96. type CustomLane struct {
  97. msg.Package `ros:"common_msgs"`
  98. Header std_msgs.Header
  99. Increment int32
  100. LaneId int32
  101. Waypoints []CustomWaypoint
  102. LaneIndex uint32
  103. Cost float32
  104. ClosestObjectDistance float32
  105. ClosestObjectVelocity float32
  106. IsBlocked bool
  107. }
  108. type CustomLaneArray struct {
  109. msg.Package `ros:"common_msgs"`
  110. Lanes []CustomLane
  111. }
  112. type CustomLidarObject struct {
  113. msg.Package `ros:"common_msgs"`
  114. Header std_msgs.Header
  115. Id uint32
  116. Label string
  117. Pose geometry_msgs.Pose
  118. Dimensions geometry_msgs.Vector3
  119. Velocity geometry_msgs.Twist
  120. Acceleration geometry_msgs.Twist
  121. Polygons geometry_msgs.PolygonStamped
  122. }
  123. type LidarObjectArray struct {
  124. msg.Package `ros:"common_msgs"`
  125. Header std_msgs.Header
  126. Objects []CustomLidarObject
  127. }
  128. type PlannerCtrl struct {
  129. msg.Package `ros:"common_msgs"`
  130. Header std_msgs.Header
  131. TargetWayMode int8
  132. TargetMapX float64 `rosname:"TargetMap_x"`
  133. TargetMapY float64 `rosname:"TargetMap_y"`
  134. TargetReflectColumnX float64 `rosname:"TargetReflectColumn_x"`
  135. TargetReflectColumnY float64 `rosname:"TargetReflectColumn_y"`
  136. LaneArray CustomLaneArray `rosname:"Lane_array"`
  137. TargetSpeedMode int8
  138. TargetSpeed float64
  139. TaskCmd int8
  140. BridgeNumber int8
  141. Bay int16
  142. ContainerPose string
  143. ContainerSize string
  144. YardBlock string
  145. YardNum string
  146. }
  147. type PlannerSpeed struct {
  148. msg.Package `ros:"common_msgs"`
  149. Header std_msgs.Header
  150. PlannerSpeedMode int8
  151. PlannerSpeed float64
  152. }
  153. type TruckActionCtrl struct {
  154. msg.Package `ros:"common_msgs"`
  155. Header std_msgs.Header
  156. AIRSEStopTriggered uint8 `rosname:"AIRS_E_Stop_Triggered"`
  157. AIRSDrivePackingN uint8 `rosname:"AIRS_Drive_Packing_N"`
  158. VehicleCtrlMode uint8
  159. RemoteCtrlSpeed float32
  160. RemoteCtrlSteering float32
  161. RemoteCtrlBrake float32
  162. }
  163. type TruckBodyCtrl struct {
  164. msg.Package `ros:"common_msgs"`
  165. Header std_msgs.Header
  166. AIRSLightLeft uint8 `rosname:"AIRS_Light_Left"`
  167. AIRSLightRight uint8 `rosname:"AIRS_Light_Right"`
  168. AIRSDriverLightForward uint8 `rosname:"AIRS_Driver_Light_Forward"`
  169. AIRSDriverLightBackward uint8 `rosname:"AIRS_Driver_Light_Backward"`
  170. AIRSWiperSpary uint8 `rosname:"AIRS_Wiper_Spary"`
  171. AIRSWiperIntermittent uint8 `rosname:"AIRS_Wiper_Intermittent"`
  172. AIRSWiperFast uint8 `rosname:"AIRS_Wiper_Fast"`
  173. AIRSHorn uint8 `rosname:"AIRS_Horn"`
  174. }
  175. type TruckCanCtl0x32 struct {
  176. msg.Package `ros:"common_msgs"`
  177. Header std_msgs.Header
  178. AIRSSettingAngleSetpoint float32 `rosname:"AIRS_Setting_Angle_Setpoint"`
  179. AIRSThrottleDamand float32 `rosname:"AIRS_Throttle_Damand"`
  180. AIRSStatusDemand int16 `rosname:"AIRS_Status_Demand"`
  181. AIRSSettingAngleSpeed float32 `rosname:"AIRS_Setting_Angle_Speed"`
  182. AIRSBrakeDemand float32 `rosname:"AIRS_Brake_Demand"`
  183. }
  184. type TruckCanCtl0x33 struct {
  185. msg.Package `ros:"common_msgs"`
  186. Header std_msgs.Header
  187. AIRSLightLeft uint8 `rosname:"AIRS_Light_Left"`
  188. AIRSLightRight uint8 `rosname:"AIRS_Light_Right"`
  189. AIRSDriverLightForward uint8 `rosname:"AIRS_Driver_Light_Forward"`
  190. AIRSDriverLightBackward uint8 `rosname:"AIRS_Driver_Light_Backward"`
  191. AIRSWiperSpary uint8 `rosname:"AIRS_Wiper_Spary"`
  192. AIRSWiperIntermittent uint8 `rosname:"AIRS_Wiper_Intermittent"`
  193. AIRSWiperFast uint8 `rosname:"AIRS_Wiper_Fast"`
  194. AIRSEStopTriggered uint8 `rosname:"AIRS_E_Stop_Triggered"`
  195. AIRSNeutral uint8 `rosname:"AIRS_Neutral"`
  196. AIRSHorn uint8 `rosname:"AIRS_Horn"`
  197. AIRSDriveD uint8 `rosname:"AIRS_Drive_D"`
  198. AIRSDriveR uint8 `rosname:"AIRS_Drive_R"`
  199. AIRSDrivePackingN uint8 `rosname:"AIRS_Drive_Packing_N"`
  200. AIRSHeartBit uint8 `rosname:"AIRS_Heart_bit"`
  201. }
  202. type TruckCanInfo struct {
  203. msg.Package `ros:"common_msgs"`
  204. Header std_msgs.Header
  205. SNYWheelAngleFeedback float32 `rosname:"SNY_Wheel_Angle_Feedback"`
  206. SNYMainMotorSpeedFeedback float32 `rosname:"SNY_main_motor_speed_Feedback"`
  207. SNYSubMotorSpeedFeedback float32 `rosname:"SNY_sub_motor_speed_Feedback"`
  208. SNYAIDriverMode uint8 `rosname:"SNY_AI_Driver_Mode"`
  209. SNYSettingPupmStatus uint8 `rosname:"SNY_Setting_pupm_Status"`
  210. SNYHighLevelFault uint8 `rosname:"SNY_High_Level_Fault"`
  211. SNYDriverGearFeedback uint8 `rosname:"SNY_Driver_Gear_Feedback"`
  212. SNYReverseGearFeedback uint8 `rosname:"SNY_Reverse_Gear_Feedback"`
  213. SNYNeutralGearFeedback uint8 `rosname:"SNY_Neutral_Gear_Feedback"`
  214. SNYPackingStatusFeedback uint8 `rosname:"SNY_Packing_Status_Feedback"`
  215. SNYBatteryLevelFeedback float32 `rosname:"SNY_Battery_Level_Feedback"`
  216. SNYVehicleSpeedFeedback float32 `rosname:"SNY_Vehicle_Speed_Feedback"`
  217. SNYHornStatus uint8 `rosname:"SNY_Horn_Status"`
  218. SNYHeartBitStatus uint8 `rosname:"SNY_Heart_bit_Status"`
  219. SNYVCUHeaith uint8 `rosname:"SNY_VCU_Heaith"`
  220. DIAIdriversSwitch uint8 `rosname:"DI_AIdrivers_Switch"`
  221. DIEmergencyStop uint8 `rosname:"DI_Emergency_Stop"`
  222. Reserved uint8 `rosname:"Reserved"`
  223. SNYWiperStatus uint8 `rosname:"SNY_Wiper_Status"`
  224. SNYStatusOfAIOS uint8 `rosname:"SNY_Status_of_AIOS"`
  225. SNYThrottlePositionFeedback float32 `rosname:"SNY_Throttle_Position_Feedback"`
  226. SNYBrakePositionFeedback float32 `rosname:"SNY_Brake_Position_Feedback"`
  227. SNYBrakeAirPressure1 float32 `rosname:"SNY_Brake_Air_Pressure_1"`
  228. SNYBrakeAirPressure2 float32 `rosname:"SNY_Brake_Air_Pressure_2"`
  229. SteerAxleSpeed float32 `rosname:"Steer_axle_speed"`
  230. RelSpeedSteerAxleLeft float32 `rosname:"Rel_speed_steer_axle_left"`
  231. RelSpeedSteerAxleRight float32 `rosname:"Rel_speed_steer_axle_right"`
  232. RelSpeedRearAxleLeft float32 `rosname:"Rel_speed_rear_axle_left"`
  233. RelSpeedRearAxleRight float32 `rosname:"Rel_speed_rear_axle_right"`
  234. SNYOutShaftTorque float32 `rosname:"SNY_Out_Shaft_Torque"`
  235. SNYOutShaftSpeed float32 `rosname:"SNY_Out_Shaft_Speed"`
  236. }
  237. type CustomWaypoint struct {
  238. msg.Package `ros:"common_msgs"`
  239. Gid int32
  240. Lid int32
  241. Pose geometry_msgs.PoseStamped
  242. Twist geometry_msgs.TwistStamped
  243. Dtlane CustomDTLane
  244. ChangeFlag int32
  245. Wpstate CustomWaypointState
  246. LaneId uint32
  247. LeftLaneId uint32
  248. RightLaneId uint32
  249. StopLineId uint32
  250. Cost float32
  251. TimeCost float32
  252. Direction uint32
  253. }
  254. type CustomWaypointState struct {
  255. msg.Package `ros:"common_msgs"`
  256. msg.Definitions `ros:"uint8 NULLSTATE=0,uint8 STR_LEFT=1,uint8 STR_RIGHT=2,uint8 STR_STRAIGHT=3,uint8 TYPE_NULL=0,uint8 TYPE_STOPLINE=1,uint8 TYPE_STOP=2"`
  257. Aid int32
  258. LanechangeState uint8
  259. SteeringState uint8
  260. AccelState uint8
  261. StoplineState uint8
  262. EventState uint64
  263. }