123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616 |
- 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"
- "time"
- )
- type BoundingBox struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Pose geometry_msgs.Pose
- Dimensions geometry_msgs.Vector3
- Value float32
- Label uint32
- }
- type Accuracy struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Accuracy float32
- }
- type BoolStamped struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Data bool
- }
- type BoundingBoxArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Boxes []BoundingBox
- }
- type BoundingBoxArrayWithCameraInfo struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Boxes BoundingBoxArray
- CameraInfo sensor_msgs.CameraInfo
- }
- type BoundingBoxMovement struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Box BoundingBox
- HandlePose geometry_msgs.Pose
- Destination geometry_msgs.PoseStamped
- }
- type Circle2D struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Radius float64
- X float64
- Y float64
- }
- type Circle2DArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Circles []Circle2D
- }
- type ClassificationResult struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Labels []uint32
- LabelNames []string
- LabelProba []float64
- Probabilities []float64
- Classifier string
- TargetNames []string
- }
- // type ClusterPointIndices struct {
- // msg.Package `ros:"jsk_recognition_msgs"`
- // Header std_msgs.Header
- // ClusterIndices []pcl_msgs.PointIndices
- // }
- type ColorHistogram struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Histogram []float32
- }
- type ColorHistogramArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Histograms []ColorHistogram
- }
- type ContactSensor struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Contact bool
- LinkName string
- }
- type ContactSensorArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Datas []ContactSensor
- }
- type DepthCalibrationParameter struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Coefficients2 []float64
- Coefficients1 []float64
- Coefficients0 []float64
- UseAbs bool
- }
- type DepthErrorResult struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- U uint32
- V uint32
- CenterU float32
- CenterV float32
- TrueDepth float32
- ObservedDepth float32
- }
- type ExifGPSInfo struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- GpsVersionId [4]uint8
- GpsLatitudeRef string
- GpsLatitude [3]float64
- GpsLongitudeRef string
- GpsLongitude [3]float64
- GpsAltitudeRef uint8
- GpsAltitude float64
- GpsTimeStamp float64
- GpsSatellites string
- GpsStatus string
- GpsMeasureMode string
- GpfSdop float64
- GpsSpeedRef string
- GpsSpeed float64
- GpsTrackRef string
- GpsTrack float64
- GpsImgDirectionRef string
- GpsImgDirection float64
- GpsMapDatum string
- GpsDestLatitudeRef string
- GpsDestLatitude [3]float64
- GpsDestLongitudeRef string
- GpsDestLongitude [3]float64
- GpsDestBearingRef string
- GpsDestBearing float64
- GpsDestDistanceRef string
- GpsDestDistance float64
- GpsDateStamp string
- GpsDifferential uint16
- GpsHpositioningError float64
- }
- type ExifTags struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- InteropIndex string
- ImageWidth uint32
- ImageHeight uint32
- BitsPerSample []uint16
- PhotometricInterpretation uint16
- ImageDescription string
- Make string
- Model string
- StripOffsets uint32
- Orientation uint16
- SamplesPerPixel uint16
- RowsPerStrip uint32
- StripByteCounts uint32
- XResolution float64
- YResolution float64
- PlanarConfiguration uint16
- ResolutionUnit uint16
- TransferFunction [768]uint16
- Software string
- DateTime string
- Artist string
- WhitePoint [2]float64
- PrimaryChromaticities [6]float64
- TileWidth uint32
- TileLength uint32
- JpgFromRawStart uint32
- JpgFromRawLength uint32
- YcbCrCoefficients [3]float64 `rosname:"ycb_cr_Coefficients"`
- YcbCrSubSampling [2]uint16
- YcbCrPositioning uint16
- ReferenceBlackWhite [6]float64
- Copyright string
- ExposureTime float64
- FNumber float64
- ExposureProgram uint16
- GpsInfo ExifGPSInfo
- Iso []uint16
- SensitivityType uint16
- StandardOutputSensitivity uint32
- RecommendedExposureIndex uint32
- IsoSpeed uint32
- IsoSpeedLatitudeyyy uint32
- IsoSpeedLatitudezzz uint32
- ExifVersion string
- DateTimeOriginal string
- DateTimeDigitized string
- OffsetTime string
- OffsetTimeOriginal string
- OffsetTimeDigitized string
- ComponentsConfiguration [4]uint8
- CompressedBitsPerPixel float64
- ShutterSpeedValue float64
- ApertureValue float64
- BrightnessValue float64
- ExposureBiasValue float64
- MaxApertureValue float64
- SubjectDistance float64
- MeteringMode uint16
- LightSource uint16
- Flash uint16
- FocalLength float64
- SubjectArea []uint16
- UserComment string
- SubsecTime string
- SubsecTimeOriginal string
- SubsecTimeDigitized string
- Temperature float64
- Humidity float64
- Pressure float64
- WaterDepth float64
- Acceleration float64
- CameraElevationAngle float64
- FlashPixVersion string
- ColorSpace uint16
- ExifImageWidth uint16
- ExifImageHeight uint16
- RelatedSoundFile string
- FlashEnergy float64
- FocalPlaneXResolution float64
- FocalPlaneYResolution float64
- FocalPlaneResolutionUnit uint16
- SubjectLocation [2]uint16
- ExposureIndex float64
- SensingMethod uint16
- SceneType string
- CustomRendered uint16
- ExposureMode uint16
- WhiteBalance uint16
- DigitalZoomRatio float64
- FocalLengthIn35mmFilm uint16 `rosname:"focal_length_in_35mm_film"`
- SceneCaptureType uint16
- GainControl uint16
- Contrast uint16
- Saturation uint16
- Sharpness uint16
- SubjectDistanceRange uint16
- ImageUniqueId string
- CameraOwnerName string
- BodySerialNumber string
- LensSpecification [4]float64
- LensMake string
- LensModel string
- LensSerialNumber string
- CompositeImage uint16
- CompositeImageCount [2]uint16
- Gamma float64
- }
- type HandPose struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- HandScore float32
- FingerNames []string
- Poses []geometry_msgs.Pose
- PointScores []float32
- }
- type HandPoseArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Poses []HandPose
- }
- type HeightmapConfig struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- MinX float32
- MaxX float32
- MinY float32
- MaxY float32
- }
- type Histogram struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Histogram []float64
- }
- type HistogramWithRange struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Bins []HistogramWithRangeBin
- }
- type HistogramWithRangeArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Histograms []HistogramWithRange
- }
- type HistogramWithRangeBin struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- MinValue float64
- MaxValue float64
- Count uint32
- }
- type HumanSkeleton struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- BoneNames []string
- Bones []Segment
- }
- type HumanSkeletonArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- HumanIds []std_msgs.Int32
- Skeletons []HumanSkeleton
- }
- type ICPResult struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Pose geometry_msgs.Pose
- Name string
- Score float64
- }
- type ImageDifferenceValue struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Difference float32
- }
- type Int32Stamped struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Data int32
- }
- type Label struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Id int32
- Name string
- }
- type LabelArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Labels []Label
- }
- type Line struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- X1 float64
- Y1 float64
- X2 float64
- Y2 float64
- }
- type LineArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Lines []Line
- }
- // type ModelCoefficientsArray struct {
- // msg.Package `ros:"jsk_recognition_msgs"`
- // Header std_msgs.Header
- // Coefficients []pcl_msgs.ModelCoefficients
- // }
- type JskRecognitionObject struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Id int32
- Name string
- ClassId int32
- ClassName string
- ImageResources []string
- MeshResource string
- Weight float32
- Dimensions geometry_msgs.Vector3
- }
- type ObjectArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Objects []JskRecognitionObject
- }
- type PanoramaInfo struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- ProjectionModel string
- ImageHeight uint32
- ImageWidth uint32
- ThetaMin float64
- ThetaMax float64
- PhiMin float64
- PhiMax float64
- }
- // TODO 暂不支持pcl_msgs
- //
- // type ParallelEdge struct {
- // msg.Package `ros:"jsk_recognition_msgs"`
- // Header std_msgs.Header
- // ClusterIndices []pcl_msgs.PointIndices
- // Coefficients []pcl_msgs.ModelCoefficients
- // }
- //
- // type ParallelEdgeArray struct {
- // msg.Package `ros:"jsk_recognition_msgs"`
- // Header std_msgs.Header
- // EdgeGroups []ParallelEdge
- // }
- type PeoplePose struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- LimbNames []string
- Poses []geometry_msgs.Pose
- Scores []float32
- }
- type PeoplePoseArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Poses []PeoplePose
- }
- type PlotData struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- msg.Definitions `ros:"uint32 SCATTER=1,uint32 LINE=2"`
- Header std_msgs.Header
- Xs []float32
- Ys []float32
- Type uint32
- Label string
- FitLine bool
- FitLineRansac bool
- }
- type PlotDataArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Data []PlotData
- NoLegend bool
- LegendFontSize float32
- MaxX float32
- MinX float32
- MinY float32
- MaxY float32
- }
- type PointsArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- CloudList []sensor_msgs.PointCloud2
- }
- type PolygonArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Polygons []geometry_msgs.PolygonStamped
- Labels []uint32
- Likelihood []float32
- }
- type PosedCameraInfo struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- CameraInfo sensor_msgs.CameraInfo
- Offset geometry_msgs.Pose
- }
- type Rect struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- X int32
- Y int32
- Width int32
- Height int32
- }
- type RectArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Rects []Rect
- }
- type RotatedRect struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- X float64
- Y float64
- Width float64
- Height float64
- Angle float64
- }
- type RotatedRectStamped struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Rect RotatedRect
- }
- type Segment struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- StartPoint geometry_msgs.Point
- EndPoint geometry_msgs.Point
- }
- type SegmentArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Segments []Segment
- }
- type SegmentStamped struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Segment Segment
- }
- type SimpleHandle struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Pose geometry_msgs.Pose
- HandleWidth float64
- }
- type SimpleOccupancyGrid struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Coefficients [4]float32
- Resolution float32
- Cells []geometry_msgs.Point
- }
- type SimpleOccupancyGridArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Grids []SimpleOccupancyGrid
- }
- type SlicedPointCloud struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- PointCloud sensor_msgs.PointCloud2
- SliceIndex uint8
- SequenceId uint8
- }
- type SnapItRequest struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- msg.Definitions `ros:"uint8 MODEL_PLANE=0,uint8 MODEL_CYLINDER=1"`
- Header std_msgs.Header
- ModelType uint8
- TargetPlane geometry_msgs.PolygonStamped
- Center geometry_msgs.PointStamped
- Direction geometry_msgs.Vector3Stamped
- Radius float64
- Height float64
- MaxDistance float64
- EpsAngle float64
- }
- type SparseImage struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Width uint32
- Height uint32
- Data16 []uint16
- Data32 []uint32
- }
- type SparseOccupancyGrid struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- OriginPose geometry_msgs.Pose
- Resolution float32
- Columns []SparseOccupancyGridColumn
- }
- type SparseOccupancyGridArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Grids []SparseOccupancyGrid
- }
- type SparseOccupancyGridCell struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- RowIndex int32
- Value float32
- }
- type SparseOccupancyGridColumn struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- ColumnIndex int32
- Cells []SparseOccupancyGridCell
- }
- type Spectrum struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Amplitude []float32
- Frequency []float32
- }
- type TimeRange struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Start time.Time
- End time.Time
- }
- type Torus struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Failure bool
- Pose geometry_msgs.Pose
- LargeRadius float64
- SmallRadius float64
- }
- type TorusArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Toruses []Torus
- }
- type TrackerStatus struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- IsTracking bool
- }
- type TrackingStatus struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- IsLost bool
- }
- type VectorArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- VectorDim int32
- Data []float64
- }
- type WeightedPoseArray struct {
- msg.Package `ros:"jsk_recognition_msgs"`
- Header std_msgs.Header
- Weights []float32
- Poses geometry_msgs.PoseArray
- }
|