123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430 |
- package pjisuv_msgs
- import (
- "github.com/bluenviron/goroslib/v2/pkg/msg"
- "github.com/bluenviron/goroslib/v2/pkg/msgs/geometry_msgs"
- "github.com/bluenviron/goroslib/v2/pkg/msgs/sensor_msgs"
- "github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
- )
- type PerceptionObjects struct {
- msg.Package `ros:"perception_msgs"`
- Header Header `rosname:"header"`
- Objs []PerceptionObject `rosname:"objs"`
- Cells []ObstacleCell `rosname:"cells"`
- }
- type PerceptionObject struct {
- msg.Package `ros:"perception_msgs"`
- Id uint32 `rosname:"id"`
- X float32 `rosname:"x"`
- Y float32 `rosname:"y"`
- Z float32 `rosname:"z"`
- Vxrel float32 `rosname:"vxrel"`
- Vyrel float32 `rosname:"vyrel"`
- Xabs float64 `rosname:"xabs"`
- Yabs float64 `rosname:"yabs"`
- Vxabs float32 `rosname:"vxabs"`
- Vyabs float32 `rosname:"vyabs"`
- Width float32 `rosname:"width"`
- Length float32 `rosname:"length"`
- Height float32 `rosname:"height"`
- Speed float32 `rosname:"speed"`
- Heading float32 `rosname:"heading"`
- Type uint8 `rosname:"type"`
- Source uint8 `rosname:"source"`
- Confidence float32 `rosname:"confidence"`
- Age uint32 `rosname:"age"`
- Velocitystatus uint8 `rosname:"velocitystatus"`
- Cells []ObstacleCell `rosname:"cells"`
- }
- type ObstacleCell struct {
- msg.Package `ros:"perception_msgs"`
- Idc int32 `rosname:"idc"`
- X float64 `rosname:"x"`
- Y float64 `rosname:"y"`
- Xg float64 `rosname:"xg"`
- Yg float64 `rosname:"yg"`
- }
- type PerceptionLocalization struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header `rosname:"header"`
- FrameUnmber uint64 `rosname:"frame_unmber"`
- FusionLevel int8 `rosname:"fusion_level"`
- Status int8 `rosname:"status"`
- Roll float64 `rosname:"roll"`
- Pitch float64 `rosname:"pitch"`
- Yaw float64 `rosname:"yaw"`
- RollStd float32 `rosname:"roll_std"`
- PitchStd float32 `rosname:"pitch_std"`
- YawStd float32 `rosname:"yaw_std"`
- Qw float64 `rosname:"qw"`
- Qx float64 `rosname:"qx"`
- Qy float64 `rosname:"qy"`
- Qz float64 `rosname:"qz"`
- AngularVelocityX float64 `rosname:"angular_velocity_x"`
- AngularVelocityY float64 `rosname:"angular_velocity_y"`
- AngularVelocityZ float64 `rosname:"angular_velocity_z"`
- Latitude float64 `rosname:"latitude"`
- Longitude float64 `rosname:"longitude"`
- Altitude float64 `rosname:"altitude"`
- LatitudeStd float32 `rosname:"latitude_std"`
- LongitudeStd float32 `rosname:"longitude_std"`
- AltitudeStd float32 `rosname:"altitude_std"`
- PositionX float64 `rosname:"position_x"`
- PositionY float64 `rosname:"position_y"`
- PositionZ float64 `rosname:"position_z"`
- PositionXStd float32 `rosname:"position_x_std"`
- PositionYStd float32 `rosname:"position_y_std"`
- PositionZStd float32 `rosname:"position_z_std"`
- VelocityX float64 `rosname:"velocity_x"`
- VelocityY float64 `rosname:"velocity_y"`
- VelocityZ float64 `rosname:"velocity_z"`
- VelocityXStd float32 `rosname:"velocity_x_std"`
- VelocityYStd float32 `rosname:"velocity_y_std"`
- VelocityZStd float32 `rosname:"velocity_z_std"`
- VelocityRx float64 `rosname:"velocity_rx"`
- VelocityRy float64 `rosname:"velocity_ry"`
- VelocityRz float64 `rosname:"velocity_rz"`
- VelocityRxStd float32 `rosname:"velocity_rx_std"`
- VelocityRyStd float32 `rosname:"velocity_ry_std"`
- VelocityRzStd float32 `rosname:"velocity_rz_std"`
- AccelX float64 `rosname:"accel_x"`
- AccelY float64 `rosname:"accel_y"`
- AccelZ float64 `rosname:"accel_z"`
- }
- type CameraObject struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- SensorId uint8
- ObjectId uint32
- DetectConfidence float32
- TypeConfidence float32
- Azimuth float32
- Yaw float32
- Type uint8
- TrackingTime float32
- TrackingLevel int8
- LaneAssignment int8
- Position geometry_msgs.Point32
- Velocity geometry_msgs.Vector3
- Acceleration geometry_msgs.Vector3
- Dimensions geometry_msgs.Vector3
- PixelCentralPoint Point2D
- PixelBoxSize Point2D
- }
- type CameraObjectList struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- FrameNumber uint64
- SensorSource int8
- Cameraobjects []CameraObject
- }
- type CameraTrafficLight struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- SensorId int8
- ObjectId int32
- DetectConfidence float32
- TypeConfidence float32
- Position geometry_msgs.Point32
- PixelCentralPoint Point2D
- PixelBoxSize Point2D
- LightColor uint8
- LightShape uint8
- }
- type CameraTrafficLightList struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- FrameId uint64
- SensorSource int8
- Cameratrafficlights []CameraTrafficLight
- }
- type CameraTrafficSign struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- SensorId int8
- ObjectId int32
- DetectConfidence float32
- TypeConfidence float32
- Position geometry_msgs.Point32
- PixelCentralPoint Point2D
- PixelBoxSize Point2D
- Type int32
- }
- type CameraTrafficSignList struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- FrameNumber uint64
- SensorSource int8
- Cameratrafficsigns []CameraTrafficSign
- }
- type PerceptionCentroids struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- Points []geometry_msgs.Point
- }
- type PerceptionCicvMovingObject struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- Id uint32
- Label string
- Probability float32
- LabelProbability float32
- MotionStatus uint32
- Color std_msgs.ColorRGBA
- Ttc float32
- Variance float32
- DataSource string
- Valid bool
- X1 float32
- Y1 float32
- X2 float32
- Y2 float32
- X3 float32
- Y3 float32
- X4 float32
- Y4 float32
- MinZ float32
- MaxZ float32
- Pose geometry_msgs.Pose
- Dimensions geometry_msgs.Vector3
- Velocity geometry_msgs.Twist
- Acceleration geometry_msgs.Twist
- VelocityReliable bool
- PoseReliable bool
- AccelerationReliable bool
- IsStatic bool
- CornerIndex int32
- ConvexHull geometry_msgs.PolygonStamped
- Cells []ObstacleCell
- Speed float32
- SpeedDirection float32
- GlobalX float32
- GlobalY float32
- Lane int32
- X int32
- Y int32
- Width int32
- Height int32
- Angle float32
- RelativeLane int32
- GlobalLane int32
- ClusterPoints sensor_msgs.PointCloud2
- BehaviorState uint8
- }
- type PerceptionCicvMovingObjects struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- Num int32
- Objects []PerceptionCicvMovingObject
- }
- type CtrlTest struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- ICPVCmdStrAngle float64 `rosname:"ICPV_Cmd_StrAngle"`
- ICPVCmdStrAngleLimit float64 `rosname:"ICPV_Cmd_StrAngleLimit"`
- ICPVCmdEPSXBWEn float64 `rosname:"ICPV_Cmd_EPSXBW_En"`
- ICPVCmdEPSDir float64 `rosname:"ICPV_Cmd_EPSDir"`
- ICPVCmdStrAngleSpd float64 `rosname:"ICPV_Cmd_StrAngleSpd"`
- ICPVCmdAccPelPosAct float64 `rosname:"ICPV_Cmd_AccPelPosAct"`
- ICPVCmdAccPelPosActInv float64 `rosname:"ICPV_Cmd_AccPelPosActInv"`
- ICPVCmdBrkPelPosAct float64 `rosname:"ICPV_Cmd_BrkPelPosAct"`
- ICPVCmdBrkPelPosActInv float64 `rosname:"ICPV_Cmd_BrkPelPosActInv"`
- ICPVCmdBrkPelEnable float64 `rosname:"ICPV_Cmd_BrkPelEnable"`
- ICPVCmdAccPelEnable float64 `rosname:"ICPV_Cmd_AccPelEnable"`
- ICPVCmdBrakeLightReq float64 `rosname:"ICPV_Cmd_BrakeLightReq"`
- ICPVCmdTgtSft float64 `rosname:"ICPV_Cmd_TgtSft"`
- ICPVCmdTgtSftEnable float64 `rosname:"ICPV_Cmd_TgtSftEnable"`
- ICPVCmdATOModEnable float64 `rosname:"ICPV_Cmd_ATOModEnable"`
- VCU1ICPVEPSDir float64 `rosname:"VCU1_ICPV_EPSDir"`
- VCU1ICPVStrAngle float64 `rosname:"VCU1_ICPV_StrAngle"`
- VCU1ICPVStrAngleSpd float64 `rosname:"VCU1_ICPV_StrAngleSpd"`
- VCU1ICPVStrAngleFb float64 `rosname:"VCU1_ICPV_StrAngleFb"`
- VCU1ICPVEPSMODE float64 `rosname:"VCU1_ICPV_EPSMODE"`
- VCU1ICPVStrAngleSpdDir float64 `rosname:"VCU1_ICPV_StrAngleSpdDir"`
- VCU1ICPVYawRate float64 `rosname:"VCU1_ICPV_YawRate"`
- VCU1ICPVLongAcc float64 `rosname:"VCU1_ICPV_LongAcc"`
- PCUICPVTMDirSts float64 `rosname:"PCU_ICPV_TMDirSts"`
- VCU1ICPVESCWhlRRSpd float64 `rosname:"VCU1_ICPV_ESCWhlRRSpd"`
- VCU1ICPVESCWhlRLSpd float64 `rosname:"VCU1_ICPV_ESCWhlRLSpd"`
- VCU1ICPVESCWhlFRSpd float64 `rosname:"VCU1_ICPV_ESCWhlFRSpd"`
- VCU1ICPVESCWhlFLSpd float64 `rosname:"VCU1_ICPV_ESCWhlFLSpd"`
- VCU1ICPVVehSpd float64 `rosname:"VCU1_ICPV_VehSpd"`
- VCUIPCVBrkLgtSts float64 `rosname:"VCU_IPCV_BrkLgtSts"`
- VUCICPVAccPed float64 `rosname:"VUC_ICPV_AccPed"`
- VUCICPVBrkPed float64 `rosname:"VUC_ICPV_BrkPed"`
- VCUICPVAccPelPosFb float64 `rosname:"VCU_ICPV_AccPelPosFb"`
- VCUICPVBrkPelPosFb float64 `rosname:"VCU_ICPV_BrkPelPosFb"`
- VCUICPVTgtSftFb float64 `rosname:"VCU_ICPV_TgtSftFb"`
- VCUICPVAccPelSta float64 `rosname:"VCU_ICPV_AccPelSta"`
- VCUICPVBrkPelSta float64 `rosname:"VCU_ICPV_BrkPelSta"`
- VCUICPVATOModFb float64 `rosname:"VCU_ICPV_ATOModFb"`
- VCUICPVVCUSta float64 `rosname:"VCU_ICPV_VCUSta"`
- VCUICPVCruiseControlSts float64 `rosname:"VCU_ICPV_CruiseControlSts"`
- VCUICPVCruiseSwitchSts float64 `rosname:"VCU_ICPV_CruiseSwitchSts"`
- VCUICPVEPBSysVCU float64 `rosname:"VCU_ICPV_EPBSysVCU"`
- VCUICPVVCUGearLevPos float64 `rosname:"VCU_ICPV_VCUGearLevPos"`
- VCU1ICPVBackDoorSts float64 `rosname:"VCU1_ICPV_BackDoorSts"`
- TargetYaw float64
- TargetVel float64
- TargetX float64
- TargetY float64
- TargetTime float64
- }
- type GpsPosition struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- PlatId int32
- ErrorCode int32
- GpsFlag int32
- PositionStatus int32 `rosname:"positionStatus"`
- GpsWeek uint32
- GpsMillisecond uint32
- Longitude float64
- Latitude float64
- Height float64
- GaussX int32 `rosname:"gaussX"`
- GaussY int32 `rosname:"gaussY"`
- Pitch int32
- Roll int32
- Azimuth int32
- NorthVelocity int32 `rosname:"northVelocity"`
- EastVelocity int32 `rosname:"eastVelocity"`
- UpVelocity int32 `rosname:"upVelocity"`
- GpsConfidence int32
- }
- type PerceptionLidarObject struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- ObjectId uint32
- Type uint8
- DetectConfidence float32
- TypeConfidence float32
- Dimensions geometry_msgs.Vector3
- ClusterPose geometry_msgs.Pose
- TrackedPose geometry_msgs.Pose
- ClusterYaw float32
- TrackedYaw float32
- Azimuth float32
- Velocity geometry_msgs.Vector3
- Acceleration geometry_msgs.Vector3
- TrackingState uint8
- Cells []ObstacleCell
- }
- type LidarObjectList struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- FrameNumber uint64
- SensorSource uint8
- Lidarobjects []PerceptionLidarObject
- Cells []ObstacleCell
- }
- type Point2D struct {
- msg.Package `ros:"perception_msgs"`
- X float64
- Y float64
- }
- type Point64 struct {
- msg.Package `ros:"perception_msgs"`
- X float64
- Y float64
- Z float64
- }
- type Polygonbus struct {
- msg.Package `ros:"perception_msgs"`
- Points []Point64
- }
- type PolygonStamped struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- Polygon Polygonbus
- }
- type RadarObject struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- IsInvalid bool
- IsMatched bool
- IsStill bool
- ClusterMask uint8
- RadarId uint8
- ObjectId uint16
- Type uint8
- LifeCount uint16
- Rcs float32
- Confidence float32
- Azimuth float32
- Position geometry_msgs.Point32
- Velocity geometry_msgs.Vector3
- Acceleration geometry_msgs.Vector3
- Dimensions geometry_msgs.Vector3
- }
- type RadarObjectList struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- Radarobjects []RadarObject
- }
- type SingleTrafficLight struct {
- msg.Package `ros:"perception_msgs"`
- Color int8
- Id string
- Confidence float32
- TrackingTime float32
- Shape int8
- }
- type TrafficLightDetection struct {
- msg.Package `ros:"perception_msgs"`
- Header Header
- TrafficLight []SingleTrafficLight
- ContainLights bool
- }
- type Trajectory struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- FrameNumber uint64
- IsValidFrame bool
- Trajectoryinfo TrajectoryInfo
- }
- type TrajectoryInfo struct {
- msg.Package `ros:"perception_msgs"`
- PathId int32
- TotalPathLength float32
- TotalPathTime float32
- DecisionType int8
- LightType int8
- LaneIds []string
- Trajectorypoints []TrajectoryPoint
- }
- type TrajectoryPoint struct {
- msg.Package `ros:"perception_msgs"`
- Position Point2D
- Velocity float32
- Heading float32
- Curvature float32
- S float32
- T float32
- A float32
- PointType int8
- }
- type UltraCell struct {
- msg.Package `ros:"perception_msgs"`
- Id int32
- DirectDist float32
- IndirectDist float32
- Status int32
- }
- type UltrasonicParking struct {
- msg.Package `ros:"perception_msgs"`
- Header std_msgs.Header
- Cell []UltraCell
- }
|