|
@@ -7,12 +7,6 @@ import (
|
|
|
"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"`
|
|
@@ -20,12 +14,6 @@ type AdjustXY struct {
|
|
|
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"`
|
|
@@ -199,16 +187,7 @@ type ExtractedPosition struct {
|
|
|
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"`
|
|
@@ -289,12 +268,7 @@ type IndicatorCmd struct {
|
|
|
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"`
|
|
@@ -331,3 +305,173 @@ type PointsImage struct {
|
|
|
ImageHeight int32 `rosname:"image_height"`
|
|
|
ImageWidth int32 `rosname:"image_width"`
|
|
|
}
|
|
|
+
|
|
|
+type ProjectionMatrix struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ ProjectionMatrix [16]float64 `rosname:"projection_matrix"`
|
|
|
+}
|
|
|
+
|
|
|
+type SteerCmd struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ Steer int32 `rosname:"steer"`
|
|
|
+}
|
|
|
+
|
|
|
+type AccelCmd struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ Accel int32 `rosname:"accel"`
|
|
|
+}
|
|
|
+type BrakeCmd struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ Brake int32 `rosname:"brake"`
|
|
|
+}
|
|
|
+type LampCmd struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ L int32 `rosname:"l"`
|
|
|
+ R int32 `rosname:"r"`
|
|
|
+}
|
|
|
+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 VehicleCmd struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ SteerCmd SteerCmd `rosname:"steer_cmd"`
|
|
|
+ AccelCmd AccelCmd `rosname:"accel_cmd"`
|
|
|
+ BrakeCmd BrakeCmd `rosname:"brake_cmd"`
|
|
|
+ LampCmd LampCmd `rosname:"lamp_cmd"`
|
|
|
+ GearCmd Gear `rosname:"gear_cmd"`
|
|
|
+ mode int32 `rosname:"mode"`
|
|
|
+ TwistCmd geometry_msgs.TwistStamped `rosname:"twist_cmd"`
|
|
|
+ CtrlCmd ControlCommand `rosname:"ctrl_cmd"`
|
|
|
+ Emergency int32 `rosname:"emergency"`
|
|
|
+}
|
|
|
+
|
|
|
+type RemoteCmd struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ VehicleCmd VehicleCmd `rosname:"vehicle_cmd"`
|
|
|
+ ControlMode int32 `rosname:"control_mode"`
|
|
|
+}
|
|
|
+type ScanImage struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ Distance []float32 `rosname:"distance"`
|
|
|
+ Intensity []float32 `rosname:"intensity"`
|
|
|
+ MaxY int32 `rosname:"max_y"`
|
|
|
+ MinY int32 `rosname:"min_y"`
|
|
|
+}
|
|
|
+type Signals struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ Signals []ExtractedPosition `rosname:"Signals"`
|
|
|
+}
|
|
|
+type State struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ VehicleState string `rosname:"vehicle_state"`
|
|
|
+ MissionState string `rosname:"mission_state"`
|
|
|
+ BehaviorState string `rosname:"behavior_state"`
|
|
|
+ MotionState string `rosname:"motion_state"`
|
|
|
+}
|
|
|
+type StateCmd struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ Cmd int32 `rosname:"cmd"`
|
|
|
+}
|
|
|
+type SyncTimeDiff struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ TimeDiff float64 `rosname:"time_diff"`
|
|
|
+ Camera std_msgs.Time `rosname:"camera"`
|
|
|
+ Lidar std_msgs.Time `rosname:"lidar"`
|
|
|
+}
|
|
|
+type SyncTimeMonitor struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header `rosname:"header"`
|
|
|
+ ImageRaw float64 `rosname:"image_raw"`
|
|
|
+ PointsRaw float64 `rosname:"points_raw"`
|
|
|
+ PointsImage float64 `rosname:"points_image"`
|
|
|
+ VscanPoints float64 `rosname:"vscan_points"`
|
|
|
+ VscanImage float64 `rosname:"vscan_image"`
|
|
|
+ ImageObj float64 `rosname:"image_obj"`
|
|
|
+ ImageObjRanged float64 `rosname:"image_obj_ranged"`
|
|
|
+ ImageObjTracked float64 `rosname:"image_obj_tracked"`
|
|
|
+ CurrentPose float64 `rosname:"current_pose"`
|
|
|
+ ObjLabel float64 `rosname:"obj_label"`
|
|
|
+ ClusterCentroids float64 `rosname:"cluster_centroids"`
|
|
|
+ ObjPose float64 `rosname:"obj_pose"`
|
|
|
+ ExecutionTime float64 `rosname:"execution_time"`
|
|
|
+ CycleTime float64 `rosname:"cycle_time"`
|
|
|
+ TimeDiff float64 `rosname:"time_diff"`
|
|
|
+}
|
|
|
+type TrafficLight struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header
|
|
|
+ TrafficLight int32
|
|
|
+}
|
|
|
+type TrafficLightResult struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header
|
|
|
+ LightId int32
|
|
|
+ RecognitionResult int32
|
|
|
+ RecognitionResultStr string
|
|
|
+ LaneId int32
|
|
|
+}
|
|
|
+type TrafficLightResultArray struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header
|
|
|
+ Results []TrafficLightResult
|
|
|
+}
|
|
|
+type TunedResult struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header
|
|
|
+ Red ColorSet `rosname:"Red"`
|
|
|
+ Yellow ColorSet `rosname:"Yellow"`
|
|
|
+ Green ColorSet `rosname:"Green"`
|
|
|
+}
|
|
|
+type VehicleLocation struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header
|
|
|
+ LaneArrayId int32
|
|
|
+ WaypointIndex int32
|
|
|
+}
|
|
|
+type VehicleStatus struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ msg.Definitions `ros:"int32 MODE_MANUAL=0,int32 MODE_AUTO=1,int32 LAMP_LEFT=1,int32 LAMP_RIGHT=2,int32 LAMP_HAZARD=3"`
|
|
|
+ Header std_msgs.Header
|
|
|
+ Tm string
|
|
|
+ Drivemode int32
|
|
|
+ Steeringmode int32
|
|
|
+ CurrentGear Gear
|
|
|
+ Speed float64
|
|
|
+ Drivepedal int32
|
|
|
+ Brakepedal int32
|
|
|
+ Angle float64
|
|
|
+ Lamp int32
|
|
|
+ Light int32
|
|
|
+}
|
|
|
+type VscanTracked struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Position geometry_msgs.Point
|
|
|
+ Orientation float32
|
|
|
+ Velocity float32
|
|
|
+ GeoRect GeometricRectangle
|
|
|
+}
|
|
|
+type VscanTrackedArray struct {
|
|
|
+ msg.Package `ros:"autoware_msgs"`
|
|
|
+ Header std_msgs.Header
|
|
|
+ ObjTracked []VscanTracked
|
|
|
+}
|