|
@@ -251,3 +251,83 @@ type ImageObj struct {
|
|
|
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"`
|
|
|
+}
|