123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333 |
- 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 AccelCmd struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Accel int32 `rosname:"accel"`
- }
- type AdjustXY struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- X int32 `rosname:"x"`
- Y int32 `rosname:"y"`
- }
- type BrakeCmd struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Brake int32 `rosname:"brake"`
- }
- type Centroids struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Points []geometry_msgs.Point `rosname:"points"`
- }
- type CloudCluster struct {
- msg.Package `ros:"autoware_msgs"`
- Id uint32 `rosname:"id"`
- Label string `rosname:"label"`
- Score float64 `rosname:"score"`
- Cloud sensor_msgs.PointCloud2 `rosname:"cloud"`
- MinPoint geometry_msgs.PointStamped `rosname:"min_point"`
- MaxPoint geometry_msgs.PointStamped `rosname:"max_point"`
- AvgPoint geometry_msgs.PointStamped `rosname:"avg_point"`
- CentroidPoint geometry_msgs.PointStamped `rosname:"centroid_point"`
- EstimatedAngle float64 `rosname:"estimated_angle"`
- Dimensions geometry_msgs.Vector3 `rosname:"dimensions"`
- EigenValues geometry_msgs.Vector3 `rosname:"eigen_values"`
- EigenVectors []geometry_msgs.Vector3 `rosname:"eigen_vectors"`
- FpfhDescriptor std_msgs.Float32MultiArray `rosname:"fpfh_descriptor"`
- BoundingBox BoundingBox `rosname:"bounding_box"`
- ConvexHull geometry_msgs.PolygonStamped `rosname:"convex_hull"`
- IndicatorState uint32 `rosname:"indicator_state"`
- }
- type CloudClusterArray struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Clusters []CloudCluster `rosname:"clusters"`
- }
- type ValueSet struct {
- msg.Package `ros:"autoware_msgs"`
- Center int32 `rosname:"center"`
- Range int32 `rosname:"range"`
- }
- type ColorSet struct {
- msg.Package `ros:"autoware_msgs"`
- Hue int32 `rosname:"Hue"`
- Sat int32 `rosname:"Sat"`
- Val int32 `rosname:"Val"`
- }
- type ControlCommand struct {
- msg.Package `ros:"autoware_msgs"`
- LinearVelocity int32 `rosname:"linear_velocity"`
- LinearAcceleration int32 `rosname:"linear_acceleration"`
- SteeringAngle int32 `rosname:"steering_angle"`
- }
- type ControlCommandStamped struct {
- msg.Package `ros:"autoware_msgs"`
- Cmd ControlCommand `rosname:"cmd"`
- }
- type DTLane struct {
- msg.Package `ros:"autoware_msgs"`
- Dist float64 `rosname:"dist"`
- Dir float64 `rosname:"dir"`
- Apara float64 `rosname:"apara"`
- R float64 `rosname:"r"`
- Slope float64 `rosname:"slope"`
- Cant float64 `rosname:"cant"`
- Lw float64 `rosname:"lw"`
- Rw float64 `rosname:"rw"`
- }
- type WaypointState struct {
- msg.Package `ros:"autoware_msgs"`
- Aid int32 `rosname:"aid"`
- NullState uint8 `rosname:"NULLSTATE"`
- LaneChangeState uint8 `rosname:"lanechange_state"`
- SteeringState uint8 `rosname:"steering_state"`
- StrLeft uint8 `rosname:"STR_LEFT"`
- StrRight uint8 `rosname:"STR_RIGHT"`
- StrStraight uint8 `rosname:"STR_STRAIGHT"`
- StrBack uint8 `rosname:"STR_BACK"`
- AccelState uint8 `rosname:"accel_state"`
- StopState uint8 `rosname:"stop_state"`
- TypeStopLine uint8 `rosname:"TYPE_STOPLINE"`
- TypeStop uint8 `rosname:"TYPE_STOP"`
- EventState uint8 `rosname:"event_state"`
- TypeEventNull uint8 `rosname:"TYPE_EVENT_NULL"`
- TypeEventGoal uint8 `rosname:"TYPE_EVENT_GOAL"`
- TypeEventMiddleGoal uint8 `rosname:"TYPE_EVENT_MIDDLE_GOAL"`
- TypeEventPositionStop uint8 `rosname:"TYPE_EVENT_POSITION_STOP"`
- TypeEventBusStop uint8 `rosname:"TYPE_EVENT_BUS_STOP"`
- TypeEventParking uint8 `rosname:"TYPE_EVENT_PARKING"`
- }
- type Waypoint struct {
- msg.Package `ros:"autoware_msgs"`
- Gid int32 `rosname:"gid"`
- Lid int32 `rosname:"lid"`
- Pose geometry_msgs.PoseStamped `rosname:"pose"`
- Twist geometry_msgs.TwistStamped `rosname:"twist"`
- DTLane DTLane `rosname:"dtlane"`
- ChangeFlag int32 `rosname:"change_flag"`
- WpState WaypointState `rosname:"wpstate"`
- LaneId uint32 `rosname:"lane_id"`
- LeftLaneId uint32 `rosname:"left_lane_id"`
- RightLaneId uint32 `rosname:"right_lane_id"`
- StopLineId uint32 `rosname:"stop_line_id"`
- Cost float32 `rosname:"cost"`
- TimeCost float32 `rosname:"time_cost"`
- Direction uint32 `rosname:"direction"`
- }
- type Lane struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Increment int32 `rosname:"increment"`
- LaneId int32 `rosname:"lane_id"`
- Waypoints []Waypoint `rosname:"waypoints"`
- LaneIndex uint32 `rosname:"lane_index"`
- Cost float32 `rosname:"cost"`
- ClosestObjectDistance float32 `rosname:"closest_object_distance"`
- ClosestObjectVelocity float32 `rosname:"closest_object_velocity"`
- IsBlocked bool `rosname:"is_blocked"`
- }
- type LaneArray struct {
- msg.Package `ros:"autoware_msgs"`
- Id int32 `rosname:"id"`
- Lanes []Lane `rosname:"lanes"`
- }
- type DetectedObject struct {
- msg.Package `ros:"autoware_msgs"`
- Id uint32 `rosname:"id"`
- Label string `rosname:"label"`
- Score float32 `rosname:"score"`
- Color std_msgs.ColorRGBA `rosname:"color"`
- Valid bool `rosname:"valid"`
- String string `rosname:"space_frame"`
- Pose geometry_msgs.Pose `rosname:"pose"`
- Dimensions geometry_msgs.Vector3 `rosname:"dimensions"`
- Variance geometry_msgs.Vector3 `rosname:"variance"`
- Velocity geometry_msgs.Twist `rosname:"velocity"`
- Acceleration geometry_msgs.Twist `rosname:"acceleration"`
- PointCloud sensor_msgs.PointCloud2 `rosname:"pointcloud"`
- ConvexHull geometry_msgs.PolygonStamped `rosname:"convex_hull"`
- CandidateTrajectories LaneArray `rosname:"candidate_trajectories"`
- PoseReliable bool `rosname:"pose_reliable"`
- VelocityReliable bool `rosname:"velocity_reliable"`
- AccelerationReliable bool `rosname:"acceleration_reliable"`
- ImageFrame string `rosname:"image_frame"`
- X int32 `rosname:"x"`
- Y int32 `rosname:"y"`
- Width int32 `rosname:"width"`
- Height int32 `rosname:"height"`
- Angle float32 `rosname:"angle"`
- RoiImage sensor_msgs.Image `rosname:"roi_image"`
- IndicatorState uint8 `rosname:"indicator_state"`
- BehaviorState uint8 `rosname:"behavior_state"`
- UserDefinedInfo []string `rosname:"user_defined_info"`
- }
- type DetectedObjectArray struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Objects []DetectedObject `rosname:"objects"`
- }
- type ExtractedPosition struct {
- msg.Package `ros:"autoware_msgs"`
- SignalId int32 `rosname:"signalId"`
- U int32 `rosname:"u"`
- V int32 `rosname:"v"`
- Radius int32 `rosname:"radius"`
- X float64 `rosname:"x"`
- Y float64 `rosname:"y"`
- Z float64 `rosname:"z"`
- Hang float64 `rosname:"hang"`
- Type int8 `rosname:"type"`
- LinkId int32 `rosname:"linkId"`
- PlId int32 `rosname:"plId"`
- }
- type Gear struct {
- msg.Package `ros:"autoware_msgs"`
- None uint8 `rosname:"NONE"`
- Park uint8 `rosname:"PARK"`
- Reverse uint8 `rosname:"REVERSE"`
- Neutral uint8 `rosname:"NEUTRAL"`
- Drive uint8 `rosname:"DRIVE"`
- Low uint8 `rosname:"LOW"`
- Gear uint8 `rosname:"gear"`
- }
- type GeometricRectangle struct {
- msg.Package `ros:"autoware_msgs"`
- Wl float32 `rosname:"wl"`
- Wr float32 `rosname:"wr"`
- Lf float32 `rosname:"lf"`
- Lb float32 `rosname:"lb"`
- }
- type ICPStat struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- ExeTime float32 `rosname:"exe_time"`
- Score float32 `rosname:"score"`
- Velocity float32 `rosname:"velocity"`
- Acceleration float32 `rosname:"acceleration"`
- UsePredictPose int32 `rosname:"use_predict_pose"`
- }
- type ImageLaneObjects struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- LaneLX1 int32 `rosname:"lane_l_x1"`
- LaneLY1 int32 `rosname:"lane_l_y1"`
- LaneLX2 int32 `rosname:"lane_l_x2"`
- LaneLY2 int32 `rosname:"lane_l_y2"`
- LaneRX1 int32 `rosname:"lane_r_x1"`
- LaneRY1 int32 `rosname:"lane_r_y1"`
- LaneRX2 int32 `rosname:"lane_r_x2"`
- LaneRY2 int32 `rosname:"lane_r_y2"`
- }
- type ImageRect struct {
- msg.Package `ros:"autoware_msgs"`
- X int32 `rosname:"x"`
- Y int32 `rosname:"y"`
- Height int32 `rosname:"height"`
- Width int32 `rosname:"width"`
- Score float32 `rosname:"score"`
- }
- type ImageObj struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Type string `rosname:"type"`
- Obj []ImageRect `rosname:"obj"`
- }
- type ImageObjects struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- CarNum uint8 `rosname:"car_num"`
- CarType []int32 `rosname:"car_type"`
- Score []float32 `rosname:"score"`
- CornerPoint []int32 `rosname:"corner_point"`
- }
- type ImageRectRanged struct {
- msg.Package `ros:"autoware_msgs"`
- Rect ImageRect `rosname:"rect"`
- Range float32 `rosname:"range"`
- MinHeight float32 `rosname:"min_height"`
- MaxHeight float32 `rosname:"max_height"`
- }
- type ImageObjRanged struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Type string `rosname:"type"`
- Obj []ImageRectRanged `rosname:"obj"`
- }
- type ImageObjTracked struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Type string `rosname:"type"`
- TotalNum uint8 `rosname:"total_num"`
- ObjId []int32 `rosname:"obj_id"`
- RectRanged []ImageRectRanged `rosname:"rect_ranged"`
- RealData []int32 `rosname:"real_data"`
- Lifespan []int32 `rosname:"lifespan"`
- }
- type IndicatorCmd struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- L int32 `rosname:"l"`
- R int32 `rosname:"r"`
- }
- type LampCmd struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- L int32 `rosname:"l"`
- R int32 `rosname:"r"`
- }
- type NDTStat struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- ExeTime float32 `rosname:"exe_time"`
- Iteration int32 `rosname:"iteration"`
- Score float32 `rosname:"score"`
- Velocity float32 `rosname:"velocity"`
- Acceleration float32 `rosname:"acceleration"`
- UsePredictPose int32 `rosname:"use_predict_pose"`
- }
- type ObjLabel struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Type string `rosname:"type"`
- ObjId []int32 `rosname:"obj_id"`
- ReprojectedPos []geometry_msgs.Point `rosname:"reprojected_pos"`
- }
- type ObjPose struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Type string `rosname:"type"`
- ObjId []int32 `rosname:"obj_id"`
- Obj []geometry_msgs.PoseArray `rosname:"obj"`
- }
- type PointsImage struct {
- msg.Package `ros:"autoware_msgs"`
- Header std_msgs.Header `rosname:"header"`
- Distance []float32 `rosname:"distance"`
- Intensity []float32 `rosname:"intensity"`
- MinHeight []float32 `rosname:"min_height"`
- MaxHeight []float32 `rosname:"max_height"`
- MaxY int32 `rosname:"max_y"`
- MinY int32 `rosname:"min_y"`
- ImageHeight int32 `rosname:"image_height"`
- ImageWidth int32 `rosname:"image_width"`
- }
|