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 Can struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header CanId uint32 Remoteflag uint8 Externflag uint8 Datalen uint8 Data [8]uint8 } type CustomControlCommand struct { msg.Package `ros:"common_msgs"` LinearVelocity float64 LinearAcceleration float64 SteeringAngle float64 } type CustomControlCommandStamped struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header Cmd CustomControlCommand } type CpsCmd struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header CpsOffset int16 CpsTimestamp uint16 } type CustomDetectedObject struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header Id uint32 Label string Score float32 Color std_msgs.ColorRGBA Valid bool SpaceFrame string Pose geometry_msgs.Pose Dimensions geometry_msgs.Vector3 Variance geometry_msgs.Vector3 Velocity geometry_msgs.Twist Acceleration geometry_msgs.Twist Pointcloud sensor_msgs.PointCloud2 ConvexHull geometry_msgs.PolygonStamped CandidateTrajectories CustomLaneArray PoseReliable bool VelocityReliable bool AccelerationReliable bool IsStatic bool CornerIndex int32 ImageFrame string X int32 Y int32 Width int32 Height int32 Angle float32 RoiImage sensor_msgs.Image IndicatorState uint8 BehaviorState uint8 UserDefinedInfo []string } type CustomDetectedObjectArray struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header Objects []CustomDetectedObject } type CustomDTLane struct { msg.Package `ros:"common_msgs"` Dist float64 Dir float64 Apara float64 R float64 Slope float64 Cant float64 Lw float64 Rw float64 } type GpsAndImu struct { msg.Package `ros:"common_msgs"` Gps sensor_msgs.NavSatFix Imu sensor_msgs.Imu } type GuiCtrl struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header StartFlag uint8 SpeedEnable uint8 TargetSpeed float32 MapPath string } type CustomLane struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header Increment int32 LaneId int32 Waypoints []CustomWaypoint LaneIndex uint32 Cost float32 ClosestObjectDistance float32 ClosestObjectVelocity float32 IsBlocked bool } type CustomLaneArray struct { msg.Package `ros:"common_msgs"` Lanes []CustomLane } type CustomLidarObject struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header Id uint32 Label string Pose geometry_msgs.Pose Dimensions geometry_msgs.Vector3 Velocity geometry_msgs.Twist Acceleration geometry_msgs.Twist Polygons geometry_msgs.PolygonStamped } type LidarObjectArray struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header Objects []CustomLidarObject } type PlannerCtrl struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header TargetWayMode int8 TargetMapX float64 `rosname:"TargetMap_x"` TargetMapY float64 `rosname:"TargetMap_y"` TargetReflectColumnX float64 `rosname:"TargetReflectColumn_x"` TargetReflectColumnY float64 `rosname:"TargetReflectColumn_y"` LaneArray CustomLaneArray `rosname:"Lane_array"` TargetSpeedMode int8 TargetSpeed float64 TaskCmd int8 BridgeNumber int8 Bay int16 ContainerPose string ContainerSize string YardBlock string YardNum string } type PlannerSpeed struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header PlannerSpeedMode int8 PlannerSpeed float64 } type TruckActionCtrl struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header AIRSEStopTriggered uint8 `rosname:"AIRS_E_Stop_Triggered"` AIRSDrivePackingN uint8 `rosname:"AIRS_Drive_Packing_N"` VehicleCtrlMode uint8 RemoteCtrlSpeed float32 RemoteCtrlSteering float32 RemoteCtrlBrake float32 } type TruckBodyCtrl struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header AIRSLightLeft uint8 `rosname:"AIRS_Light_Left"` AIRSLightRight uint8 `rosname:"AIRS_Light_Right"` AIRSDriverLightForward uint8 `rosname:"AIRS_Driver_Light_Forward"` AIRSDriverLightBackward uint8 `rosname:"AIRS_Driver_Light_Backward"` AIRSWiperSpary uint8 `rosname:"AIRS_Wiper_Spary"` AIRSWiperIntermittent uint8 `rosname:"AIRS_Wiper_Intermittent"` AIRSWiperFast uint8 `rosname:"AIRS_Wiper_Fast"` AIRSHorn uint8 `rosname:"AIRS_Horn"` } type TruckCanCtl0x32 struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header AIRSSettingAngleSetpoint float32 `rosname:"AIRS_Setting_Angle_Setpoint"` AIRSThrottleDamand float32 `rosname:"AIRS_Throttle_Damand"` AIRSStatusDemand int16 `rosname:"AIRS_Status_Demand"` AIRSSettingAngleSpeed float32 `rosname:"AIRS_Setting_Angle_Speed"` AIRSBrakeDemand float32 `rosname:"AIRS_Brake_Demand"` } type TruckCanCtl0x33 struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header AIRSLightLeft uint8 `rosname:"AIRS_Light_Left"` AIRSLightRight uint8 `rosname:"AIRS_Light_Right"` AIRSDriverLightForward uint8 `rosname:"AIRS_Driver_Light_Forward"` AIRSDriverLightBackward uint8 `rosname:"AIRS_Driver_Light_Backward"` AIRSWiperSpary uint8 `rosname:"AIRS_Wiper_Spary"` AIRSWiperIntermittent uint8 `rosname:"AIRS_Wiper_Intermittent"` AIRSWiperFast uint8 `rosname:"AIRS_Wiper_Fast"` AIRSEStopTriggered uint8 `rosname:"AIRS_E_Stop_Triggered"` AIRSNeutral uint8 `rosname:"AIRS_Neutral"` AIRSHorn uint8 `rosname:"AIRS_Horn"` AIRSDriveD uint8 `rosname:"AIRS_Drive_D"` AIRSDriveR uint8 `rosname:"AIRS_Drive_R"` AIRSDrivePackingN uint8 `rosname:"AIRS_Drive_Packing_N"` AIRSHeartBit uint8 `rosname:"AIRS_Heart_bit"` } type TruckCanInfo struct { msg.Package `ros:"common_msgs"` Header std_msgs.Header SNYWheelAngleFeedback float32 `rosname:"SNY_Wheel_Angle_Feedback"` SNYMainMotorSpeedFeedback float32 `rosname:"SNY_main_motor_speed_Feedback"` SNYSubMotorSpeedFeedback float32 `rosname:"SNY_sub_motor_speed_Feedback"` SNYAIDriverMode uint8 `rosname:"SNY_AI_Driver_Mode"` SNYSettingPupmStatus uint8 `rosname:"SNY_Setting_pupm_Status"` SNYHighLevelFault uint8 `rosname:"SNY_High_Level_Fault"` SNYDriverGearFeedback uint8 `rosname:"SNY_Driver_Gear_Feedback"` SNYReverseGearFeedback uint8 `rosname:"SNY_Reverse_Gear_Feedback"` SNYNeutralGearFeedback uint8 `rosname:"SNY_Neutral_Gear_Feedback"` SNYPackingStatusFeedback uint8 `rosname:"SNY_Packing_Status_Feedback"` SNYBatteryLevelFeedback float32 `rosname:"SNY_Battery_Level_Feedback"` SNYVehicleSpeedFeedback float32 `rosname:"SNY_Vehicle_Speed_Feedback"` SNYHornStatus uint8 `rosname:"SNY_Horn_Status"` SNYHeartBitStatus uint8 `rosname:"SNY_Heart_bit_Status"` SNYVCUHeaith uint8 `rosname:"SNY_VCU_Heaith"` DIAIdriversSwitch uint8 `rosname:"DI_AIdrivers_Switch"` DIEmergencyStop uint8 `rosname:"DI_Emergency_Stop"` Reserved uint8 `rosname:"Reserved"` SNYWiperStatus uint8 `rosname:"SNY_Wiper_Status"` SNYStatusOfAIOS uint8 `rosname:"SNY_Status_of_AIOS"` SNYThrottlePositionFeedback float32 `rosname:"SNY_Throttle_Position_Feedback"` SNYBrakePositionFeedback float32 `rosname:"SNY_Brake_Position_Feedback"` SNYBrakeAirPressure1 float32 `rosname:"SNY_Brake_Air_Pressure_1"` SNYBrakeAirPressure2 float32 `rosname:"SNY_Brake_Air_Pressure_2"` SteerAxleSpeed float32 `rosname:"Steer_axle_speed"` RelSpeedSteerAxleLeft float32 `rosname:"Rel_speed_steer_axle_left"` RelSpeedSteerAxleRight float32 `rosname:"Rel_speed_steer_axle_right"` RelSpeedRearAxleLeft float32 `rosname:"Rel_speed_rear_axle_left"` RelSpeedRearAxleRight float32 `rosname:"Rel_speed_rear_axle_right"` SNYOutShaftTorque float32 `rosname:"SNY_Out_Shaft_Torque"` SNYOutShaftSpeed float32 `rosname:"SNY_Out_Shaft_Speed"` } type CustomWaypoint struct { msg.Package `ros:"common_msgs"` Gid int32 Lid int32 Pose geometry_msgs.PoseStamped Twist geometry_msgs.TwistStamped Dtlane CustomDTLane ChangeFlag int32 Wpstate CustomWaypointState LaneId uint32 LeftLaneId uint32 RightLaneId uint32 StopLineId uint32 Cost float32 TimeCost float32 Direction uint32 } type CustomWaypointState struct { msg.Package `ros:"common_msgs"` 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"` Aid int32 LanechangeState uint8 SteeringState uint8 AccelState uint8 StoplineState uint8 EventState uint64 }