From a643d220e863559cba2d39d3caf30ab181bc046e Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 24 Oct 2024 14:59:46 -0400 Subject: [PATCH 01/51] Init craziness --- components/camera/camera.go | 3 + components/camera/camera_test.go | 8 +- components/camera/client.go | 4 + components/camera/client_test.go | 96 +++++++++---------- components/camera/collector.go | 2 +- components/camera/fake/camera_test.go | 8 +- components/camera/fake/image_file_test.go | 18 +--- components/camera/ffmpeg/ffmpeg_test.go | 5 +- components/camera/replaypcd/replaypcd.go | 14 +++ components/camera/replaypcd/replaypcd_test.go | 5 - components/camera/server.go | 2 +- components/camera/server_test.go | 82 ++++++++-------- .../camera/transformpipeline/classifier.go | 13 ++- .../transformpipeline/classifier_test.go | 2 +- .../camera/transformpipeline/composed.go | 30 +++--- .../camera/transformpipeline/composed_test.go | 17 +--- .../camera/transformpipeline/depth_edges.go | 13 ++- .../transformpipeline/depth_edges_test.go | 35 ++++--- .../camera/transformpipeline/detector.go | 13 ++- .../camera/transformpipeline/detector_test.go | 8 +- components/camera/transformpipeline/mods.go | 51 +++++----- .../camera/transformpipeline/mods_test.go | 92 ++++++++++-------- .../camera/transformpipeline/pipeline.go | 18 ++-- .../camera/transformpipeline/pipeline_test.go | 28 +++--- .../camera/transformpipeline/preprocessing.go | 13 ++- .../camera/transformpipeline/segmenter.go | 13 ++- .../transformpipeline/segmenter_test.go | 12 --- .../camera/transformpipeline/transform.go | 5 +- .../camera/transformpipeline/undistort.go | 13 ++- .../transformpipeline/undistort_test.go | 56 +++++++---- components/camera/videosource/webcam.go | 4 + components/camera/videosourcewrappers.go | 5 + robot/client/client_test.go | 16 ++-- robot/impl/local_robot_test.go | 2 +- .../datamanager/builtin/builtin_sync_test.go | 37 +++---- services/datamanager/builtin/builtin_test.go | 9 +- .../vision/obstaclesdepth/obstacles_depth.go | 4 +- services/vision/vision.go | 6 +- testutils/inject/camera.go | 30 +++--- 39 files changed, 384 insertions(+), 408 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 1cd42ca8a00..6ff8b979045 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -119,6 +119,9 @@ type VideoSource interface { // that may have a MIME type hint dictated in the context via gostream.WithMIMETypeHint. Stream(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) + // GetImage returns a single image that may have a MIME type hint dictated in the context via gostream.WithMIMETypeHint. + GetImage(ctx context.Context) (image.Image, func(), error) + // NextPointCloud returns the next immediately available point cloud, not necessarily one // a part of a sequence. In the future, there could be streaming of point clouds. NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index 1d4392c285d..035fcf5817d 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -183,9 +183,7 @@ func TestCameraWithNoProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, _, err := camera.ReadImage( - gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)), - noProj2) + img, _, err := noProj2.GetImage(gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG))) test.That(t, err, test.ShouldBeNil) depthImg := img.(*rimage.DepthMap) @@ -234,9 +232,7 @@ func TestCameraWithProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, _, err := camera.ReadImage( - gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG), - cam2) + img, _, err := cam2.GetImage(gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG)) test.That(t, err, test.ShouldBeNil) depthImg := img.(*rimage.DepthMap) diff --git a/components/camera/client.go b/components/camera/client.go index 852f6548577..aeb6826f9a4 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -228,6 +228,10 @@ func (c *client) Stream( return stream, nil } +func (c *client) GetImage(ctx context.Context) (image.Image, func(), error) { + return c.Read(ctx) +} + func (c *client) Images(ctx context.Context) ([]NamedImage, resource.ResponseMetadata, error) { ctx, span := trace.StartSpan(ctx, "camera::client::Images") defer span.End() diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 0e905f44b57..a0cd0f39dfc 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -99,13 +99,11 @@ func TestClient(t *testing.T) { ts := time.UnixMilli(12345) return images, resource.ResponseMetadata{CapturedAt: ts}, nil } - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return imgPng, func() {}, nil - })), nil + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + imageReleasedMu.Lock() + imageReleased = true + imageReleasedMu.Unlock() + return imgPng, func() {}, nil } // depth camera injectCameraDepth := &inject.Camera{} @@ -127,13 +125,11 @@ func TestClient(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return depthImg, func() {}, nil - })), nil + injectCameraDepth.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + imageReleasedMu.Lock() + imageReleased = true + imageReleasedMu.Unlock() + return depthImg, func() {}, nil } // bad camera injectCamera2 := &inject.Camera{} @@ -146,8 +142,8 @@ func TestClient(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return nil, errStreamFailed + injectCamera2.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + return nil, func() {}, errGetImageFailed } resources := map[resource.Name]camera.Camera{ @@ -181,7 +177,7 @@ func TestClient(t *testing.T) { camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA) - frame, _, err := camera.ReadImage(ctx, camera1Client) + frame, _, err := camera1Client.GetImage(ctx) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) @@ -232,7 +228,7 @@ func TestClient(t *testing.T) { ctx := gostream.WithMIMETypeHint( context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)) - frame, _, err := camera.ReadImage(ctx, client) + frame, _, err := client.GetImage(ctx) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) @@ -251,9 +247,9 @@ func TestClient(t *testing.T) { client2, err := resourceAPI.RPCClient(context.Background(), conn, "", camera.Named(failCameraName), logger) test.That(t, err, test.ShouldBeNil) - _, _, err = camera.ReadImage(context.Background(), client2) + _, _, err = client2.GetImage(context.Background()) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) _, err = client2.NextPointCloud(context.Background()) test.That(t, err, test.ShouldNotBeNil) @@ -272,63 +268,63 @@ func TestClient(t *testing.T) { camClient, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, extra, test.ShouldBeEmpty) - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } ctx := context.Background() - _, _, err = camera.ReadImage(ctx, camClient) + _, _, err = camClient.GetImage(ctx) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra["hello"], test.ShouldEqual, "world") - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } // one kvp created with camera.Extra ext := camera.Extra{"hello": "world"} ctx = camera.NewContext(ctx, ext) - _, _, err = camera.ReadImage(ctx, camClient) + _, _, err = camClient.GetImage(ctx) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } // one kvp created with data.FromDMContextKey ctx = context.WithValue(context.Background(), data.FromDMContextKey{}, true) - _, _, err = camera.ReadImage(ctx, camClient) + _, _, err = camClient.GetImage(ctx) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, len(extra), test.ShouldEqual, 2) test.That(t, extra["hello"], test.ShouldEqual, "world") test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } // merge values from data and camera ext = camera.Extra{"hello": "world"} ctx = camera.NewContext(ctx, ext) - _, _, err = camera.ReadImage(ctx, camClient) + _, _, err = camClient.GetImage(ctx) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) test.That(t, conn.Close(), test.ShouldBeNil) }) @@ -453,16 +449,14 @@ func TestClientLazyImage(t *testing.T) { imgPng, err := png.Decode(bytes.NewReader(imgBuf.Bytes())) test.That(t, err, test.ShouldBeNil) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - mimeType, _ := rutils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, rutils.MimeTypeRawRGBA)) - switch mimeType { - case rutils.MimeTypePNG: - return imgPng, func() {}, nil - default: - return nil, nil, errInvalidMimeType - } - })), nil + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + mimeType, _ := rutils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, rutils.MimeTypeRawRGBA)) + switch mimeType { + case rutils.MimeTypePNG: + return imgPng, func() {}, nil + default: + return nil, nil, errInvalidMimeType + } } resources := map[resource.Name]camera.Camera{ @@ -484,7 +478,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG) - frame, _, err := camera.ReadImage(ctx, camera1Client) + frame, _, err := camera1Client.GetImage(ctx) test.That(t, err, test.ShouldBeNil) // Should always lazily decode test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) @@ -492,7 +486,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) ctx = gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)) - frame, _, err = camera.ReadImage(ctx, camera1Client) + frame, _, err = camera1Client.GetImage(ctx) test.That(t, err, test.ShouldBeNil) test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) frameLazy = frame.(*rimage.LazyEncodedImage) @@ -582,10 +576,8 @@ func TestClientStreamAfterClose(t *testing.T) { injectCamera.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - return img, func() {}, nil - })), nil + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + return img, func() {}, nil } // Register CameraService API in our gRPC server. diff --git a/components/camera/collector.go b/components/camera/collector.go index 5079f547e46..7b922f8a700 100644 --- a/components/camera/collector.go +++ b/components/camera/collector.go @@ -96,7 +96,7 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d ctx = context.WithValue(ctx, data.FromDMContextKey{}, true) - img, release, err := ReadImage(ctx, camera) + img, release, err := camera.GetImage(ctx) if err != nil { // A modular filter component can be created to filter the readings from a component. The error ErrNoCaptureToStore // is used in the datamanager to exclude readings from being captured and stored. diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index d4ba8e70860..97127cd8ae6 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -104,9 +104,7 @@ func cameraTest( distortion transform.Distorter, ) { t.Helper() - stream, err := cam.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - img, _, err := stream.Next(context.Background()) + img, _, err := cam.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, width) test.That(t, img.Bounds().Dy(), test.ShouldEqual, height) @@ -185,9 +183,7 @@ func TestRTPPassthrough(t *testing.T) { camera, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) - stream, err := camera.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - img, _, err := stream.Next(context.Background()) + img, _, err := camera.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index ab090f90a56..b0b0c41037b 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -26,9 +26,6 @@ func TestPCD(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - _, err = cam.Stream(ctx) - test.That(t, err, test.ShouldBeNil) - pc, err := cam.NextPointCloud(ctx) test.That(t, err, test.ShouldBeNil) test.That(t, pc.Size(), test.ShouldEqual, 628) @@ -45,13 +42,10 @@ func TestPCD(t *testing.T) { cam, err = newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - stream, err := cam.Stream(ctx) - test.That(t, err, test.ShouldBeNil) - readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) - strmImg, _, err := stream.Next(ctx) + strmImg, _, err := cam.GetImage(ctx) test.That(t, err, test.ShouldBeNil) test.That(t, strmImg, test.ShouldResemble, readInImage) test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds()) @@ -68,16 +62,13 @@ func TestColor(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - stream, err := cam.Stream(ctx) - test.That(t, err, test.ShouldBeNil) - _, err = cam.NextPointCloud(ctx) test.That(t, err, test.ShouldNotBeNil) readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) - strmImg, _, err := stream.Next(ctx) + strmImg, _, err := cam.GetImage(ctx) test.That(t, err, test.ShouldBeNil) test.That(t, strmImg, test.ShouldResemble, readInImage) test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds()) @@ -108,13 +99,10 @@ func TestColorOddResolution(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - stream, err := cam.Stream(ctx) - test.That(t, err, test.ShouldBeNil) - readInImage, err := rimage.NewImageFromFile(imgFilePath) test.That(t, err, test.ShouldBeNil) - strmImg, _, err := stream.Next(ctx) + strmImg, _, err := cam.GetImage(ctx) test.That(t, err, test.ShouldBeNil) expectedBounds := image.Rect(0, 0, readInImage.Bounds().Dx()-1, readInImage.Bounds().Dy()-1) diff --git a/components/camera/ffmpeg/ffmpeg_test.go b/components/camera/ffmpeg/ffmpeg_test.go index f3b36771ea3..4c74b1fac94 100644 --- a/components/camera/ffmpeg/ffmpeg_test.go +++ b/components/camera/ffmpeg/ffmpeg_test.go @@ -17,13 +17,10 @@ func TestFFMPEGCamera(t *testing.T) { path := artifact.MustPath("components/camera/ffmpeg/testsrc.mpg") cam, err := NewFFMPEGCamera(ctx, &Config{VideoPath: path}, logger) test.That(t, err, test.ShouldBeNil) - stream, err := cam.Stream(ctx) - test.That(t, err, test.ShouldBeNil) for i := 0; i < 5; i++ { - _, _, err := stream.Next(ctx) + _, _, err := cam.GetImage(ctx) test.That(t, err, test.ShouldBeNil) } - test.That(t, stream.Close(context.Background()), test.ShouldBeNil) test.That(t, cam.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/replaypcd/replaypcd.go b/components/camera/replaypcd/replaypcd.go index 9740d99e5a7..dcd9c3d8a41 100644 --- a/components/camera/replaypcd/replaypcd.go +++ b/components/camera/replaypcd/replaypcd.go @@ -4,6 +4,7 @@ package replaypcd import ( "bytes" "context" + "image" "net/http" "sync" "time" @@ -346,6 +347,19 @@ func (replay *pcdCamera) Stream(ctx context.Context, errHandlers ...gostream.Err return stream, errors.New("Stream is unimplemented") } +func (replay *pcdCamera) GetImage(ctx context.Context) (image.Image, func(), error) { + stream, err := replay.Stream(ctx) + if err != nil { + return nil, func() {}, err + } + defer func() { + if err := stream.Close(ctx); err != nil { + replay.logger.Errorf("stream failed to close: %w", err) + } + }() + return stream.Next(ctx) +} + // Close stops replay camera, closes the channels and its connections to the cloud. func (replay *pcdCamera) Close(ctx context.Context) error { replay.mu.Lock() diff --git a/components/camera/replaypcd/replaypcd_test.go b/components/camera/replaypcd/replaypcd_test.go index 90b397edc21..39a60203010 100644 --- a/components/camera/replaypcd/replaypcd_test.go +++ b/components/camera/replaypcd/replaypcd_test.go @@ -660,11 +660,6 @@ func TestReplayPCDUnimplementedFunctions(t *testing.T) { replayCamera, _, serverClose, err := createNewReplayPCDCamera(ctx, t, replayCamCfg, true) test.That(t, err, test.ShouldBeNil) - t.Run("Stream", func(t *testing.T) { - _, err := replayCamera.Stream(ctx, nil) - test.That(t, err.Error(), test.ShouldEqual, "Stream is unimplemented") - }) - err = replayCamera.Close(ctx) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/server.go b/components/camera/server.go index 0f8fb8b2a19..b891b2e2506 100644 --- a/components/camera/server.go +++ b/components/camera/server.go @@ -93,7 +93,7 @@ func (s *serviceServer) GetImage( // network. Just to be discarded. img, release, err = castedCam.Read(ctx) default: - img, release, err = ReadImage(gostream.WithMIMETypeHint(ctx, req.MimeType), cam) + img, release, err = cam.GetImage(gostream.WithMIMETypeHint(ctx, req.MimeType)) } if err != nil { return nil, err diff --git a/components/camera/server_test.go b/components/camera/server_test.go index db5c366e917..ee054331669 100644 --- a/components/camera/server_test.go +++ b/components/camera/server_test.go @@ -31,7 +31,7 @@ var ( errGeneratePointCloudFailed = errors.New("can't generate next point cloud") errPropertiesFailed = errors.New("can't get camera properties") errCameraProjectorFailed = errors.New("can't get camera properties") - errStreamFailed = errors.New("can't generate stream") + errGetImageFailed = errors.New("can't get image") errCameraUnimplemented = errors.New("not found") ) @@ -112,25 +112,23 @@ func TestServer(t *testing.T) { return projA, nil } wooMIME := "image/woohoo" - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - mimeType, _ := utils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, utils.MimeTypeRawRGBA)) - switch mimeType { - case "", utils.MimeTypeRawRGBA: - return img, func() {}, nil - case utils.MimeTypePNG: - return imgPng, func() {}, nil - case utils.MimeTypeJPEG: - return imgJpeg, func() {}, nil - case "image/woohoo": - return rimage.NewLazyEncodedImage([]byte{1, 2, 3}, mimeType), func() {}, nil - default: - return nil, nil, errInvalidMimeType - } - })), nil + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + imageReleasedMu.Lock() + imageReleased = true + imageReleasedMu.Unlock() + mimeType, _ := utils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, utils.MimeTypeRawRGBA)) + switch mimeType { + case "", utils.MimeTypeRawRGBA: + return img, func() {}, nil + case utils.MimeTypePNG: + return imgPng, func() {}, nil + case utils.MimeTypeJPEG: + return imgJpeg, func() {}, nil + case "image/woohoo": + return rimage.NewLazyEncodedImage([]byte{1, 2, 3}, mimeType), func() {}, nil + default: + return nil, nil, errInvalidMimeType + } } // depth camera depthImage := rimage.NewEmptyDepthMap(10, 20) @@ -155,13 +153,11 @@ func TestServer(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return depthImage, func() {}, nil - })), nil + injectCameraDepth.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + imageReleasedMu.Lock() + imageReleased = true + imageReleasedMu.Unlock() + return depthImage, func() {}, nil } // bad camera injectCamera2.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { @@ -173,8 +169,8 @@ func TestServer(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return nil, errStreamFailed + injectCamera2.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + return nil, func() {}, errGetImageFailed } // does a depth camera transfer its depth image properly @@ -284,7 +280,7 @@ func TestServer(t *testing.T) { // bad camera _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{Name: failCameraName, MimeType: utils.MimeTypeRawRGBA}) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) }) t.Run("GetImage with lazy", func(t *testing.T) { @@ -367,7 +363,7 @@ func TestServer(t *testing.T) { _, err = cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{Name: failCameraName}) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) }) t.Run("GetPointCloud", func(t *testing.T) { @@ -435,11 +431,11 @@ func TestServer(t *testing.T) { }) t.Run("GetImage with extra", func(t *testing.T) { - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, extra, test.ShouldBeEmpty) - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ @@ -447,14 +443,14 @@ func TestServer(t *testing.T) { }) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra["hello"], test.ShouldEqual, "world") - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } ext, err := goprotoutils.StructToStructPb(camera.Extra{"hello": "world"}) @@ -466,15 +462,15 @@ func TestServer(t *testing.T) { }) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } // one kvp created with data.FromDMContextKey @@ -487,15 +483,15 @@ func TestServer(t *testing.T) { }) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { extra, ok := camera.FromContext(ctx) test.That(t, ok, test.ShouldBeTrue) test.That(t, len(extra), test.ShouldEqual, 2) test.That(t, extra["hello"], test.ShouldEqual, "world") test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, errStreamFailed + return nil, func() {}, errGetImageFailed } // use values from data and camera @@ -513,7 +509,7 @@ func TestServer(t *testing.T) { }) test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error()) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) }) } diff --git a/components/camera/transformpipeline/classifier.go b/components/camera/transformpipeline/classifier.go index 5db1f7c43e8..6dc62d6fcfc 100644 --- a/components/camera/transformpipeline/classifier.go +++ b/components/camera/transformpipeline/classifier.go @@ -9,7 +9,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/robot" @@ -28,7 +27,7 @@ type classifierConfig struct { // classifierSource takes an image from the camera, and overlays labels from the classifier. type classifierSource struct { - stream gostream.VideoStream + src camera.VideoSource classifierName string maxClassifications uint32 labelFilter classification.Postprocessor @@ -38,8 +37,8 @@ type classifierSource struct { func newClassificationsTransform( ctx context.Context, - source gostream.VideoSource, r robot.Robot, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { + source camera.VideoSource, r robot.Robot, am utils.AttributeMap, +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*classifierConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err @@ -66,7 +65,7 @@ func newClassificationsTransform( maxClassifications = conf.MaxClassifications } classifier := &classifierSource{ - gostream.NewEmbeddedVideoStream(source), + source, conf.ClassifierName, maxClassifications, labelFilter, @@ -92,7 +91,7 @@ func (cs *classifierSource) Read(ctx context.Context) (image.Image, func(), erro return nil, nil, errors.Wrap(err, "source_classifier can't find vision service") } // get image from source camera - img, release, err := cs.stream.Next(ctx) + img, release, err := cs.src.GetImage(ctx) if err != nil { return nil, nil, errors.Wrap(err, "could not get next source image") } @@ -111,5 +110,5 @@ func (cs *classifierSource) Read(ctx context.Context) (image.Image, func(), erro } func (cs *classifierSource) Close(ctx context.Context) error { - return cs.stream.Close(ctx) + return cs.src.Close(ctx) } diff --git a/components/camera/transformpipeline/classifier_test.go b/components/camera/transformpipeline/classifier_test.go index 122d13de236..27d1e47815f 100644 --- a/components/camera/transformpipeline/classifier_test.go +++ b/components/camera/transformpipeline/classifier_test.go @@ -116,7 +116,7 @@ func TestClassifierSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) defer classifier.Close(ctx) - resImg, _, err := camera.ReadImage(ctx, classifier) + resImg, _, err := classifier.GetImage(ctx) test.That(t, err, test.ShouldBeNil) ovImg := rimage.ConvertImage(resImg) diff --git a/components/camera/transformpipeline/composed.go b/components/camera/transformpipeline/composed.go index 333d9682c3e..d6fe17c71bb 100644 --- a/components/camera/transformpipeline/composed.go +++ b/components/camera/transformpipeline/composed.go @@ -8,7 +8,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -19,13 +18,13 @@ import ( // depthToPretty takes a depth image and turns into a colorful image, with blue being // farther away, and red being closest. Actual depth information is lost in the transform. type depthToPretty struct { - originalStream gostream.VideoStream - cameraModel *transform.PinholeCameraModel + src camera.VideoSource + cameraModel *transform.PinholeCameraModel } -func propsFromVideoSource(ctx context.Context, source gostream.VideoSource) (camera.Properties, error) { +func propsFromVideoSource(ctx context.Context, source camera.VideoSource) (camera.Properties, error) { var camProps camera.Properties - //nolint:staticcheck + if cameraSrc, ok := source.(camera.Camera); ok { props, err := cameraSrc.Properties(ctx) if err != nil { @@ -38,9 +37,9 @@ func propsFromVideoSource(ctx context.Context, source gostream.VideoSource) (cam func newDepthToPrettyTransform( ctx context.Context, - source gostream.VideoSource, + source camera.VideoSource, stream camera.ImageType, -) (gostream.VideoSource, camera.ImageType, error) { +) (camera.VideoSource, camera.ImageType, error) { if stream != camera.DepthStream { return nil, camera.UnspecifiedStream, errors.Errorf("source has stream type %s, depth_to_pretty only supports depth stream inputs", stream) @@ -55,10 +54,9 @@ func newDepthToPrettyTransform( if props.DistortionParams != nil { cameraModel.Distortion = props.DistortionParams } - depthStream := gostream.NewEmbeddedVideoStream(source) reader := &depthToPretty{ - originalStream: depthStream, - cameraModel: &cameraModel, + src: source, + cameraModel: &cameraModel, } src, err := camera.NewVideoSourceFromReader(ctx, reader, &cameraModel, camera.ColorStream) if err != nil { @@ -70,7 +68,7 @@ func newDepthToPrettyTransform( func (dtp *depthToPretty) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::depthToPretty::Read") defer span.End() - i, release, err := dtp.originalStream.Next(ctx) + i, release, err := dtp.src.GetImage(ctx) if err != nil { return nil, nil, err } @@ -82,7 +80,7 @@ func (dtp *depthToPretty) Read(ctx context.Context) (image.Image, func(), error) } func (dtp *depthToPretty) Close(ctx context.Context) error { - return dtp.originalStream.Close(ctx) + return dtp.src.Close(ctx) } func (dtp *depthToPretty) PointCloud(ctx context.Context) (pointcloud.PointCloud, error) { @@ -91,7 +89,7 @@ func (dtp *depthToPretty) PointCloud(ctx context.Context) (pointcloud.PointCloud if dtp.cameraModel == nil || dtp.cameraModel.PinholeCameraIntrinsics == nil { return nil, errors.Wrapf(transform.ErrNoIntrinsics, "depthToPretty transform cannot project to pointcloud") } - i, release, err := dtp.originalStream.Next(ctx) + i, release, err := dtp.src.GetImage(ctx) if err != nil { return nil, err } @@ -111,16 +109,16 @@ type overlayConfig struct { // overlaySource overlays the depth and color 2D images in order to debug the alignment of the two images. type overlaySource struct { - src gostream.VideoSource + src camera.VideoSource cameraModel *transform.PinholeCameraModel } func newOverlayTransform( ctx context.Context, - src gostream.VideoSource, + src camera.VideoSource, stream camera.ImageType, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*overlayConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err diff --git a/components/camera/transformpipeline/composed_test.go b/components/camera/transformpipeline/composed_test.go index bf288cf938e..52dfbcaaf07 100644 --- a/components/camera/transformpipeline/composed_test.go +++ b/components/camera/transformpipeline/composed_test.go @@ -9,23 +9,13 @@ import ( "go.viam.com/test" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" - "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/testutils/inject" "go.viam.com/rdk/utils" ) -type streamTest struct{} - -// Next will stream a color image. -func (*streamTest) Next(ctx context.Context) (image.Image, func(), error) { - return rimage.NewImage(1280, 720), func() {}, nil -} -func (*streamTest) Close(ctx context.Context) error { return nil } - func TestComposed(t *testing.T) { // create pointcloud source and fake robot robot := &inject.Robot{} @@ -35,9 +25,6 @@ func TestComposed(t *testing.T) { p := pointcloud.New() return p, p.Set(pointcloud.NewVector(0, 0, 0), pointcloud.NewColoredData(color.NRGBA{255, 1, 2, 255})) } - cloudSource.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return &streamTest{}, nil - } cloudSource.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } @@ -66,14 +53,14 @@ func TestComposed(t *testing.T) { myOverlay, stream, err := newOverlayTransform(context.Background(), cloudSource, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - pic, _, err := camera.ReadImage(context.Background(), myOverlay) + pic, _, err := myOverlay.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, pic.Bounds(), test.ShouldResemble, image.Rect(0, 0, 1280, 720)) myPipeline, err := newTransformPipeline(context.Background(), cloudSource, conf, robot, logger) test.That(t, err, test.ShouldBeNil) defer myPipeline.Close(context.Background()) - pic, _, err = camera.ReadImage(context.Background(), myPipeline) + pic, _, err = myPipeline.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, pic.Bounds(), test.ShouldResemble, image.Rect(0, 0, 1280, 720)) diff --git a/components/camera/transformpipeline/depth_edges.go b/components/camera/transformpipeline/depth_edges.go index e5c0f558126..82d02195910 100644 --- a/components/camera/transformpipeline/depth_edges.go +++ b/components/camera/transformpipeline/depth_edges.go @@ -8,7 +8,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" @@ -23,13 +22,13 @@ type depthEdgesConfig struct { // depthEdgesSource applies a Canny Edge Detector to the depth map. type depthEdgesSource struct { - stream gostream.VideoStream + src camera.VideoSource detector *rimage.CannyEdgeDetector blurRadius float64 } -func newDepthEdgesTransform(ctx context.Context, source gostream.VideoSource, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { +func newDepthEdgesTransform(ctx context.Context, source camera.VideoSource, am utils.AttributeMap, +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*depthEdgesConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err @@ -45,7 +44,7 @@ func newDepthEdgesTransform(ctx context.Context, source gostream.VideoSource, am cameraModel.Distortion = props.DistortionParams } canny := rimage.NewCannyDericheEdgeDetectorWithParameters(conf.HiThresh, conf.LoThresh, true) - videoSrc := &depthEdgesSource{gostream.NewEmbeddedVideoStream(source), canny, 3.0} + videoSrc := &depthEdgesSource{source, canny, 3.0} src, err := camera.NewVideoSourceFromReader(ctx, videoSrc, &cameraModel, camera.DepthStream) if err != nil { return nil, camera.UnspecifiedStream, err @@ -57,7 +56,7 @@ func newDepthEdgesTransform(ctx context.Context, source gostream.VideoSource, am func (os *depthEdgesSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::depthEdges::Read") defer span.End() - i, closer, err := os.stream.Next(ctx) + i, closer, err := os.src.GetImage(ctx) if err != nil { return nil, nil, err } @@ -73,5 +72,5 @@ func (os *depthEdgesSource) Read(ctx context.Context) (image.Image, func(), erro } func (os *depthEdgesSource) Close(ctx context.Context) error { - return os.stream.Close(ctx) + return os.src.Close(ctx) } diff --git a/components/camera/transformpipeline/depth_edges_test.go b/components/camera/transformpipeline/depth_edges_test.go index fdb193a4c7d..9deded44067 100644 --- a/components/camera/transformpipeline/depth_edges_test.go +++ b/components/camera/transformpipeline/depth_edges_test.go @@ -7,13 +7,11 @@ import ( "image" "testing" - "github.com/pion/mediadevices/pkg/prop" "go.viam.com/test" "go.viam.com/utils/artifact" "go.viam.com/rdk/components/camera" "go.viam.com/rdk/components/camera/fake" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/depthadapter" @@ -25,16 +23,17 @@ func TestDepthSource(t *testing.T) { img, err := rimage.NewDepthMapFromFile( context.Background(), artifact.MustPath("rimage/board1_gray_small.png")) test.That(t, err, test.ShouldBeNil) - source := &fake.StaticSource{DepthImg: img} + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am := utils.AttributeMap{ "high_threshold": 0.85, "low_threshold": 0.40, "blur_radius": 3.0, } - ds, stream, err := newDepthEdgesTransform(context.Background(), gostream.NewVideoSource(source, prop.Video{}), am) + ds, stream, err := newDepthEdgesTransform(context.Background(), source, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - _, _, err = camera.ReadImage(context.Background(), ds) + _, _, err = ds.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, ds.Close(context.Background()), test.ShouldBeNil) } @@ -57,16 +56,17 @@ func (h *depthSourceTestHelper) Process( pCtx.GotDebugImage(dm.ToPrettyPicture(0, rimage.MaxDepth), "aligned-depth") // create edge map - source := &fake.StaticSource{DepthImg: dm} + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: dm}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am := utils.AttributeMap{ "high_threshold": 0.85, "low_threshold": 0.40, "blur_radius": 3.0, } - ds, stream, err := newDepthEdgesTransform(context.Background(), gostream.NewVideoSource(source, prop.Video{}), am) + ds, stream, err := newDepthEdgesTransform(context.Background(), source, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - edges, _, err := camera.ReadImage(context.Background(), ds) + edges, _, err := ds.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, ds.Close(context.Background()), test.ShouldBeNil) @@ -78,12 +78,13 @@ func (h *depthSourceTestHelper) Process( pCtx.GotDebugPointCloud(fixedPointCloud, "aligned-pointcloud") // preprocess depth map - source = &fake.StaticSource{DepthImg: dm} - rs, stream, err := newDepthPreprocessTransform(context.Background(), gostream.NewVideoSource(source, prop.Video{})) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: dm}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) + rs, stream, err := newDepthPreprocessTransform(context.Background(), source) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - output, _, err := camera.ReadImage(context.Background(), rs) + output, _, err := rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) preprocessed, err := rimage.ConvertImageToDepthMap(context.Background(), output) test.That(t, err, test.ShouldBeNil) @@ -94,11 +95,17 @@ func (h *depthSourceTestHelper) Process( test.That(t, preprocessedPointCloud.MetaData().HasColor, test.ShouldBeFalse) pCtx.GotDebugPointCloud(preprocessedPointCloud, "preprocessed-aligned-pointcloud") - source = &fake.StaticSource{DepthImg: preprocessed} - ds, stream, err = newDepthEdgesTransform(context.Background(), gostream.NewVideoSource(source, prop.Video{}), am) + source, err = camera.NewVideoSourceFromReader( + context.Background(), + &fake.StaticSource{DepthImg: preprocessed}, + nil, + camera.UnspecifiedStream, + ) + test.That(t, err, test.ShouldBeNil) + ds, stream, err = newDepthEdgesTransform(context.Background(), source, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - processedEdges, _, err := camera.ReadImage(context.Background(), ds) + processedEdges, _, err := ds.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, ds.Close(context.Background()), test.ShouldBeNil) diff --git a/components/camera/transformpipeline/detector.go b/components/camera/transformpipeline/detector.go index 241103353d0..65134e4d2af 100644 --- a/components/camera/transformpipeline/detector.go +++ b/components/camera/transformpipeline/detector.go @@ -9,7 +9,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/robot" @@ -27,7 +26,7 @@ type detectorConfig struct { // detectorSource takes an image from the camera, and overlays the detections from the detector. type detectorSource struct { - stream gostream.VideoStream + src camera.VideoSource detectorName string labelFilter objectdetection.Postprocessor // must build from ValidLabels confFilter objectdetection.Postprocessor @@ -36,10 +35,10 @@ type detectorSource struct { func newDetectionsTransform( ctx context.Context, - source gostream.VideoSource, + source camera.VideoSource, r robot.Robot, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*detectorConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err @@ -62,7 +61,7 @@ func newDetectionsTransform( } labelFilter := objectdetection.NewLabelFilter(validLabels) detector := &detectorSource{ - gostream.NewEmbeddedVideoStream(source), + source, conf.DetectorName, labelFilter, confFilter, @@ -85,7 +84,7 @@ func (ds *detectorSource) Read(ctx context.Context) (image.Image, func(), error) return nil, nil, fmt.Errorf("source_detector cant find vision service: %w", err) } // get image from source camera - img, release, err := ds.stream.Next(ctx) + img, release, err := ds.src.GetImage(ctx) if err != nil { return nil, nil, fmt.Errorf("could not get next source image: %w", err) } @@ -105,5 +104,5 @@ func (ds *detectorSource) Read(ctx context.Context) (image.Image, func(), error) } func (ds *detectorSource) Close(ctx context.Context) error { - return ds.stream.Close(ctx) + return ds.src.Close(ctx) } diff --git a/components/camera/transformpipeline/detector_test.go b/components/camera/transformpipeline/detector_test.go index 45f5444dccd..2fa0005eb30 100644 --- a/components/camera/transformpipeline/detector_test.go +++ b/components/camera/transformpipeline/detector_test.go @@ -165,7 +165,7 @@ func TestColorDetectionSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) defer detector.Close(ctx) - resImg, _, err := camera.ReadImage(ctx, detector) + resImg, _, err := detector.GetImage(ctx) test.That(t, err, test.ShouldBeNil) ovImg := rimage.ConvertImage(resImg) test.That(t, ovImg.GetXY(852, 431), test.ShouldResemble, rimage.Red) @@ -188,7 +188,7 @@ func TestTFLiteDetectionSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) defer detector.Close(ctx) - resImg, _, err := camera.ReadImage(ctx, detector) + resImg, _, err := detector.GetImage(ctx) test.That(t, err, test.ShouldBeNil) ovImg := rimage.ConvertImage(resImg) test.That(t, ovImg.GetXY(624, 402), test.ShouldResemble, rimage.Red) @@ -213,7 +213,7 @@ func BenchmarkColorDetectionSource(b *testing.B) { b.ResetTimer() // begin benchmarking for i := 0; i < b.N; i++ { - _, _, _ = camera.ReadImage(ctx, detector) + _, _, _ = detector.GetImage(ctx) } test.That(b, detector.Close(context.Background()), test.ShouldBeNil) } @@ -235,7 +235,7 @@ func BenchmarkTFLiteDetectionSource(b *testing.B) { b.ResetTimer() // begin benchmarking for i := 0; i < b.N; i++ { - _, _, _ = camera.ReadImage(ctx, detector) + _, _, _ = detector.GetImage(ctx) } test.That(b, detector.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/transformpipeline/mods.go b/components/camera/transformpipeline/mods.go index 776d51856fa..20b542d38d6 100644 --- a/components/camera/transformpipeline/mods.go +++ b/components/camera/transformpipeline/mods.go @@ -11,7 +11,6 @@ import ( "golang.org/x/image/draw" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" @@ -25,14 +24,14 @@ type rotateConfig struct { // rotateSource is the source to be rotated and the kind of image type. type rotateSource struct { - originalStream gostream.VideoStream - stream camera.ImageType - angle float64 + src camera.VideoSource + stream camera.ImageType + angle float64 } // newRotateTransform creates a new rotation transform. -func newRotateTransform(ctx context.Context, source gostream.VideoSource, stream camera.ImageType, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { +func newRotateTransform(ctx context.Context, source camera.VideoSource, stream camera.ImageType, am utils.AttributeMap, +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*rotateConfig](am) if err != nil { return nil, camera.UnspecifiedStream, errors.Wrap(err, "cannot parse rotate attribute map") @@ -52,7 +51,7 @@ func newRotateTransform(ctx context.Context, source gostream.VideoSource, stream if props.DistortionParams != nil { cameraModel.Distortion = props.DistortionParams } - reader := &rotateSource{gostream.NewEmbeddedVideoStream(source), stream, conf.Angle} + reader := &rotateSource{source, stream, conf.Angle} src, err := camera.NewVideoSourceFromReader(ctx, reader, &cameraModel, stream) if err != nil { return nil, camera.UnspecifiedStream, err @@ -64,7 +63,7 @@ func newRotateTransform(ctx context.Context, source gostream.VideoSource, stream func (rs *rotateSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::rotate::Read") defer span.End() - orig, release, err := rs.originalStream.Next(ctx) + orig, release, err := rs.src.GetImage(ctx) if err != nil { return nil, nil, err } @@ -86,7 +85,7 @@ func (rs *rotateSource) Read(ctx context.Context) (image.Image, func(), error) { // Close closes the original stream. func (rs *rotateSource) Close(ctx context.Context) error { - return rs.originalStream.Close(ctx) + return rs.src.Close(ctx) } // resizeConfig are the attributes for a resize transform. @@ -96,16 +95,16 @@ type resizeConfig struct { } type resizeSource struct { - originalStream gostream.VideoStream - stream camera.ImageType - height int - width int + src camera.VideoSource + stream camera.ImageType + height int + width int } // newResizeTransform creates a new resize transform. func newResizeTransform( - ctx context.Context, source gostream.VideoSource, stream camera.ImageType, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { + ctx context.Context, source camera.VideoSource, stream camera.ImageType, am utils.AttributeMap, +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*resizeConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err @@ -117,7 +116,7 @@ func newResizeTransform( return nil, camera.UnspecifiedStream, errors.New("new height for resize transform cannot be 0") } - reader := &resizeSource{gostream.NewEmbeddedVideoStream(source), stream, conf.Height, conf.Width} + reader := &resizeSource{source, stream, conf.Height, conf.Width} src, err := camera.NewVideoSourceFromReader(ctx, reader, nil, stream) if err != nil { return nil, camera.UnspecifiedStream, err @@ -129,7 +128,7 @@ func newResizeTransform( func (rs *resizeSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::resize::Read") defer span.End() - orig, release, err := rs.originalStream.Next(ctx) + orig, release, err := rs.src.GetImage(ctx) if err != nil { return nil, nil, err } @@ -153,7 +152,7 @@ func (rs *resizeSource) Read(ctx context.Context) (image.Image, func(), error) { // Close closes the original stream. func (rs *resizeSource) Close(ctx context.Context) error { - return rs.originalStream.Close(ctx) + return rs.src.Close(ctx) } // cropConfig are the attributes for a crop transform. @@ -165,15 +164,15 @@ type cropConfig struct { } type cropSource struct { - originalStream gostream.VideoStream - imgType camera.ImageType - cropWindow image.Rectangle + src camera.VideoSource + imgType camera.ImageType + cropWindow image.Rectangle } // newCropTransform creates a new crop transform. func newCropTransform( - ctx context.Context, source gostream.VideoSource, stream camera.ImageType, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { + ctx context.Context, source camera.VideoSource, stream camera.ImageType, am utils.AttributeMap, +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*cropConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err @@ -189,7 +188,7 @@ func newCropTransform( } cropRect := image.Rect(conf.XMin, conf.YMin, conf.XMax, conf.YMax) - reader := &cropSource{gostream.NewEmbeddedVideoStream(source), stream, cropRect} + reader := &cropSource{source, stream, cropRect} src, err := camera.NewVideoSourceFromReader(ctx, reader, nil, stream) if err != nil { return nil, camera.UnspecifiedStream, err @@ -201,7 +200,7 @@ func newCropTransform( func (cs *cropSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::crop::Read") defer span.End() - orig, release, err := cs.originalStream.Next(ctx) + orig, release, err := cs.src.GetImage(ctx) if err != nil { return nil, nil, err } @@ -229,5 +228,5 @@ func (cs *cropSource) Read(ctx context.Context) (image.Image, func(), error) { // Close closes the original stream. func (cs *cropSource) Close(ctx context.Context) error { - return cs.originalStream.Close(ctx) + return cs.src.Close(ctx) } diff --git a/components/camera/transformpipeline/mods_test.go b/components/camera/transformpipeline/mods_test.go index 721319a9bdf..12cbd8722b4 100644 --- a/components/camera/transformpipeline/mods_test.go +++ b/components/camera/transformpipeline/mods_test.go @@ -30,8 +30,9 @@ func TestCrop(t *testing.T) { test.That(t, err, test.ShouldBeNil) // test depth source - source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: dm}, prop.Video{}) - out, _, err := camera.ReadImage(context.Background(), source) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: dm}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) + out, _, err := source.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -39,7 +40,7 @@ func TestCrop(t *testing.T) { rs, stream, err := newCropTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - out, _, err = camera.ReadImage(context.Background(), rs) + out, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 10) @@ -48,8 +49,9 @@ func TestCrop(t *testing.T) { test.That(t, source.Close(context.Background()), test.ShouldBeNil) // test color source - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) - out, _, err = camera.ReadImage(context.Background(), source) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) + out, _, err = source.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -58,7 +60,7 @@ func TestCrop(t *testing.T) { rs, stream, err = newCropTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - out, _, err = camera.ReadImage(context.Background(), rs) + out, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 10) @@ -69,18 +71,18 @@ func TestCrop(t *testing.T) { rs, stream, err = newCropTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - out, _, err = camera.ReadImage(context.Background(), rs) + out, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 1) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 1) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) - // error - crop limits are outside of original image + // error - crop limits are outside of original image am = utils.AttributeMap{"x_min_px": 1000, "x_max_px": 2000, "y_min_px": 300, "y_max_px": 400} rs, stream, err = newCropTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - _, _, err = camera.ReadImage(context.Background(), rs) + _, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "cropped image to 0 pixels") test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -107,8 +109,9 @@ func TestResizeColor(t *testing.T) { "height_px": 20, "width_px": 30, } - source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) - out, _, err := camera.ReadImage(context.Background(), source) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) + out, _, err := source.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -116,7 +119,7 @@ func TestResizeColor(t *testing.T) { rs, stream, err := newResizeTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - out, _, err = camera.ReadImage(context.Background(), rs) + out, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 30) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 20) @@ -133,8 +136,9 @@ func TestResizeDepth(t *testing.T) { "height_px": 40, "width_px": 60, } - source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: img}, prop.Video{}) - out, _, err := camera.ReadImage(context.Background(), source) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) + out, _, err := source.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -142,7 +146,7 @@ func TestResizeDepth(t *testing.T) { rs, stream, err := newResizeTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - out, _, err = camera.ReadImage(context.Background(), rs) + out, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 60) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 40) @@ -154,7 +158,8 @@ func TestRotateColorSource(t *testing.T) { img, err := rimage.NewImageFromFile(artifact.MustPath("rimage/board1_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am := utils.AttributeMap{ "angle_degs": 180, } @@ -162,7 +167,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err := camera.ReadImage(context.Background(), rs) + rawImage, _, err := rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -179,7 +184,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImageDefault, _, err := camera.ReadImage(context.Background(), rsDefault) + rawImageDefault, _, err := rsDefault.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -207,7 +212,8 @@ func TestRotateColorSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": 90, } @@ -215,7 +221,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -238,7 +244,8 @@ func TestRotateColorSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": -90, } @@ -246,7 +253,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -269,7 +276,8 @@ func TestRotateColorSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": 270, } @@ -277,7 +285,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -300,7 +308,8 @@ func TestRotateColorSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": 0, // no-op } @@ -308,7 +317,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -336,7 +345,8 @@ func TestRotateDepthSource(t *testing.T) { context.Background(), artifact.MustPath("rimage/board1_gray_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: pc}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: pc}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am := utils.AttributeMap{ "angle_degs": 180, } @@ -344,7 +354,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err := camera.ReadImage(context.Background(), rs) + rawImage, _, err := rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -362,7 +372,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImageDefault, _, err := camera.ReadImage(context.Background(), rsDefault) + rawImageDefault, _, err := rsDefault.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -388,7 +398,8 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{DepthImg: pc}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: pc}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": 90, } @@ -396,7 +407,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -419,7 +430,8 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{DepthImg: pc}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: pc}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": -90, } @@ -427,7 +439,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -450,7 +462,8 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{DepthImg: pc}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: pc}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": 270, } @@ -458,7 +471,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -481,7 +494,8 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, rs.Close(context.Background()), test.ShouldBeNil) test.That(t, source.Close(context.Background()), test.ShouldBeNil) - source = gostream.NewVideoSource(&fake.StaticSource{DepthImg: pc}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: pc}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{ "angle_degs": 0, // no-op } @@ -489,7 +503,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = camera.ReadImage(context.Background(), rs) + rawImage, _, err = rs.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -529,7 +543,7 @@ func BenchmarkColorRotate(b *testing.B) { b.ResetTimer() for n := 0; n < b.N; n++ { - camera.ReadImage(context.Background(), rs) + rs.GetImage(context.Background()) } test.That(b, rs.Close(context.Background()), test.ShouldBeNil) test.That(b, source.Close(context.Background()), test.ShouldBeNil) @@ -553,7 +567,7 @@ func BenchmarkDepthRotate(b *testing.B) { b.ResetTimer() for n := 0; n < b.N; n++ { - camera.ReadImage(context.Background(), rs) + rs.GetImage(context.Background()) } test.That(b, rs.Close(context.Background()), test.ShouldBeNil) test.That(b, source.Close(context.Background()), test.ShouldBeNil) diff --git a/components/camera/transformpipeline/pipeline.go b/components/camera/transformpipeline/pipeline.go index 254913d941b..0b86b0091a6 100644 --- a/components/camera/transformpipeline/pipeline.go +++ b/components/camera/transformpipeline/pipeline.go @@ -13,7 +13,6 @@ import ( "go.uber.org/multierr" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" @@ -89,7 +88,7 @@ func (cfg *transformConfig) Validate(path string) ([]string, error) { func newTransformPipeline( ctx context.Context, - source gostream.VideoSource, + source camera.VideoSource, cfg *transformConfig, r robot.Robot, logger logging.Logger, @@ -101,7 +100,7 @@ func newTransformPipeline( return nil, errors.New("pipeline has no transforms in it") } // check if the source produces a depth image or color image - img, release, err := camera.ReadImage(ctx, source) + img, release, err := source.GetImage(ctx) var streamType camera.ImageType if err != nil { @@ -117,7 +116,7 @@ func newTransformPipeline( release() } // loop through the pipeline and create the image flow - pipeline := make([]gostream.VideoSource, 0, len(cfg.Pipeline)) + pipeline := make([]camera.VideoSource, 0, len(cfg.Pipeline)) lastSource := source for _, tr := range cfg.Pipeline { src, newStreamType, err := buildTransform(ctx, r, lastSource, streamType, tr, cfg.Source) @@ -128,19 +127,18 @@ func newTransformPipeline( lastSource = src streamType = newStreamType } - lastSourceStream := gostream.NewEmbeddedVideoStream(lastSource) cameraModel := camera.NewPinholeModelWithBrownConradyDistortion(cfg.CameraParameters, cfg.DistortionParameters) return camera.NewVideoSourceFromReader( ctx, - transformPipeline{pipeline, lastSourceStream, cfg.CameraParameters, logger}, + transformPipeline{pipeline, lastSource, cfg.CameraParameters, logger}, &cameraModel, streamType, ) } type transformPipeline struct { - pipeline []gostream.VideoSource - stream gostream.VideoStream + pipeline []camera.VideoSource + src camera.VideoSource intrinsicParameters *transform.PinholeCameraIntrinsics logger logging.Logger } @@ -148,7 +146,7 @@ type transformPipeline struct { func (tp transformPipeline) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::Read") defer span.End() - return tp.stream.Next(ctx) + return tp.src.GetImage(ctx) } func (tp transformPipeline) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { @@ -176,5 +174,5 @@ func (tp transformPipeline) Close(ctx context.Context) error { return src.Close(ctx) }()) } - return multierr.Combine(tp.stream.Close(ctx), errs) + return multierr.Combine(tp.src.Close(ctx), errs) } diff --git a/components/camera/transformpipeline/pipeline_test.go b/components/camera/transformpipeline/pipeline_test.go index b96ea0a9596..d01e337b32b 100644 --- a/components/camera/transformpipeline/pipeline_test.go +++ b/components/camera/transformpipeline/pipeline_test.go @@ -35,7 +35,7 @@ func TestTransformPipelineColor(t *testing.T) { source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) src, err := camera.WrapVideoSourceWithProjector(context.Background(), source, nil, camera.ColorStream) test.That(t, err, test.ShouldBeNil) - inImg, _, err := camera.ReadImage(context.Background(), src) + inImg, _, err := src.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -43,7 +43,7 @@ func TestTransformPipelineColor(t *testing.T) { color, err := newTransformPipeline(context.Background(), src, transformConf, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := camera.ReadImage(context.Background(), color) + outImg, _, err := color.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 20) @@ -81,7 +81,7 @@ func TestTransformPipelineDepth(t *testing.T) { source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: dm}, prop.Video{}) src, err := camera.WrapVideoSourceWithProjector(context.Background(), source, nil, camera.DepthStream) test.That(t, err, test.ShouldBeNil) - inImg, _, err := camera.ReadImage(context.Background(), src) + inImg, _, err := src.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -89,7 +89,7 @@ func TestTransformPipelineDepth(t *testing.T) { depth, err := newTransformPipeline(context.Background(), src, transformConf, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := camera.ReadImage(context.Background(), depth) + outImg, _, err := depth.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 40) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 30) @@ -130,11 +130,13 @@ func TestTransformPipelineDepth2(t *testing.T) { dm, err := rimage.NewDepthMapFromFile( context.Background(), artifact.MustPath("rimage/board1_gray_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: dm}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: dm}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) + // first depth transform depth1, err := newTransformPipeline(context.Background(), source, transform1, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := camera.ReadImage(context.Background(), depth1) + outImg, _, err := depth1.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 20) @@ -142,7 +144,7 @@ func TestTransformPipelineDepth2(t *testing.T) { // second depth image depth2, err := newTransformPipeline(context.Background(), source, transform2, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err = camera.ReadImage(context.Background(), depth2) + outImg, _, err = depth2.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 40) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 30) @@ -160,7 +162,8 @@ func TestNullPipeline(t *testing.T) { img, err := rimage.NewImageFromFile(artifact.MustPath("rimage/board1_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) _, err = newTransformPipeline(context.Background(), source, transform1, r, logger) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "pipeline has no transforms") @@ -171,7 +174,7 @@ func TestNullPipeline(t *testing.T) { } pipe, err := newTransformPipeline(context.Background(), source, transform2, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := camera.ReadImage(context.Background(), pipe) // should not transform anything + outImg, _, err := pipe.GetImage(context.Background()) // should not transform anything test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -185,7 +188,8 @@ func TestPipeIntoPipe(t *testing.T) { img, err := rimage.NewImageFromFile(artifact.MustPath("rimage/board1_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) intrinsics1 := &transform.PinholeCameraIntrinsics{Width: 128, Height: 72} transform1 := &transformConfig{ @@ -204,7 +208,7 @@ func TestPipeIntoPipe(t *testing.T) { pipe1, err := newTransformPipeline(context.Background(), source, transform1, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := camera.ReadImage(context.Background(), pipe1) + outImg, _, err := pipe1.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -215,7 +219,7 @@ func TestPipeIntoPipe(t *testing.T) { // transform pipeline into pipeline pipe2, err := newTransformPipeline(context.Background(), pipe1, transform2, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err = camera.ReadImage(context.Background(), pipe2) + outImg, _, err = pipe2.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 20) diff --git a/components/camera/transformpipeline/preprocessing.go b/components/camera/transformpipeline/preprocessing.go index 79ff11d5e00..db113f4e74c 100644 --- a/components/camera/transformpipeline/preprocessing.go +++ b/components/camera/transformpipeline/preprocessing.go @@ -8,19 +8,18 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" ) // preprocessDepthTransform applies pre-processing functions to depth maps in order to smooth edges and fill holes. type preprocessDepthTransform struct { - stream gostream.VideoStream + src camera.VideoSource } -func newDepthPreprocessTransform(ctx context.Context, source gostream.VideoSource, -) (gostream.VideoSource, camera.ImageType, error) { - reader := &preprocessDepthTransform{gostream.NewEmbeddedVideoStream(source)} +func newDepthPreprocessTransform(ctx context.Context, source camera.VideoSource, +) (camera.VideoSource, camera.ImageType, error) { + reader := &preprocessDepthTransform{source} props, err := propsFromVideoSource(ctx, source) if err != nil { @@ -43,7 +42,7 @@ func newDepthPreprocessTransform(ctx context.Context, source gostream.VideoSourc func (os *preprocessDepthTransform) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::depthPreprocess::Read") defer span.End() - i, release, err := os.stream.Next(ctx) + i, release, err := os.src.GetImage(ctx) if err != nil { return nil, nil, err } @@ -59,5 +58,5 @@ func (os *preprocessDepthTransform) Read(ctx context.Context) (image.Image, func } func (os *preprocessDepthTransform) Close(ctx context.Context) error { - return os.stream.Close(ctx) + return os.src.Close(ctx) } diff --git a/components/camera/transformpipeline/segmenter.go b/components/camera/transformpipeline/segmenter.go index 3e0f306e2e5..7b737863ab9 100644 --- a/components/camera/transformpipeline/segmenter.go +++ b/components/camera/transformpipeline/segmenter.go @@ -8,7 +8,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/robot" @@ -24,7 +23,7 @@ type segmenterConfig struct { // segmenterSource takes a pointcloud from the camera and applies a segmenter to it. type segmenterSource struct { - stream gostream.VideoStream + src camera.VideoSource cameraName string segmenterName string r robot.Robot @@ -32,11 +31,11 @@ type segmenterSource struct { func newSegmentationsTransform( ctx context.Context, - source gostream.VideoSource, + source camera.VideoSource, r robot.Robot, am utils.AttributeMap, sourceString string, -) (gostream.VideoSource, camera.ImageType, error) { +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*segmenterConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err @@ -48,7 +47,7 @@ func newSegmentationsTransform( } segmenter := &segmenterSource{ - gostream.NewEmbeddedVideoStream(source), + source, sourceString, conf.SegmenterName, r, @@ -108,7 +107,7 @@ func (ss *segmenterSource) NextPointCloud(ctx context.Context) (pointcloud.Point // Read returns the image if the stream is valid, else error. func (ss *segmenterSource) Read(ctx context.Context) (image.Image, func(), error) { - img, release, err := ss.stream.Next(ctx) + img, release, err := ss.src.GetImage(ctx) if err != nil { return nil, nil, fmt.Errorf("could not get next source image: %w", err) } @@ -117,5 +116,5 @@ func (ss *segmenterSource) Read(ctx context.Context) (image.Image, func(), error // Close closes the underlying stream. func (ss *segmenterSource) Close(ctx context.Context) error { - return ss.stream.Close(ctx) + return ss.src.Close(ctx) } diff --git a/components/camera/transformpipeline/segmenter_test.go b/components/camera/transformpipeline/segmenter_test.go index a00242a3999..4268d393982 100644 --- a/components/camera/transformpipeline/segmenter_test.go +++ b/components/camera/transformpipeline/segmenter_test.go @@ -2,14 +2,12 @@ package transformpipeline import ( "context" - "image" "image/color" "testing" "go.viam.com/test" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" pc "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" @@ -26,11 +24,6 @@ func TestTransformSegmenterProps(t *testing.T) { vizServ := &inject.VisionService{} logger := logging.NewTestLogger(t) - cam.StreamFunc = func(ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.MediaStream[image.Image], error) { - return &streamTest{}, nil - } cam.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } @@ -90,11 +83,6 @@ func TestTransformSegmenterFunctionality(t *testing.T) { vizServ := &inject.VisionService{} logger := logging.NewTestLogger(t) - cam.StreamFunc = func(ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.MediaStream[image.Image], error) { - return &streamTest{}, nil - } cam.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } diff --git a/components/camera/transformpipeline/transform.go b/components/camera/transformpipeline/transform.go index c8d401997e4..2b23743bb5a 100644 --- a/components/camera/transformpipeline/transform.go +++ b/components/camera/transformpipeline/transform.go @@ -7,7 +7,6 @@ import ( "github.com/pkg/errors" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/robot" "go.viam.com/rdk/utils" ) @@ -137,11 +136,11 @@ func (Transformation) JSONSchema() *jsonschema.Schema { func buildTransform( ctx context.Context, r robot.Robot, - source gostream.VideoSource, + source camera.VideoSource, stream camera.ImageType, tr Transformation, sourceString string, -) (gostream.VideoSource, camera.ImageType, error) { +) (camera.VideoSource, camera.ImageType, error) { switch transformType(tr.Type) { case transformTypeUnspecified, transformTypeIdentity: return source, stream, nil diff --git a/components/camera/transformpipeline/undistort.go b/components/camera/transformpipeline/undistort.go index 7254fe2f64e..fc4501ac3c1 100644 --- a/components/camera/transformpipeline/undistort.go +++ b/components/camera/transformpipeline/undistort.go @@ -8,7 +8,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" @@ -23,14 +22,14 @@ type undistortConfig struct { // undistortSource will undistort the original image according to the Distortion parameters // within the intrinsic parameters. type undistortSource struct { - originalStream gostream.VideoStream + originalSource camera.VideoSource stream camera.ImageType cameraParams *transform.PinholeCameraModel } func newUndistortTransform( - ctx context.Context, source gostream.VideoSource, stream camera.ImageType, am utils.AttributeMap, -) (gostream.VideoSource, camera.ImageType, error) { + ctx context.Context, source camera.VideoSource, stream camera.ImageType, am utils.AttributeMap, +) (camera.VideoSource, camera.ImageType, error) { conf, err := resource.TransformAttributeMap[*undistortConfig](am) if err != nil { return nil, camera.UnspecifiedStream, err @@ -40,7 +39,7 @@ func newUndistortTransform( } cameraModel := camera.NewPinholeModelWithBrownConradyDistortion(conf.CameraParams, conf.DistortionParams) reader := &undistortSource{ - gostream.NewEmbeddedVideoStream(source), + source, stream, &cameraModel, } @@ -55,7 +54,7 @@ func newUndistortTransform( func (us *undistortSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::undistort::Read") defer span.End() - orig, release, err := us.originalStream.Next(ctx) + orig, release, err := us.originalSource.GetImage(ctx) if err != nil { return nil, nil, err } @@ -84,5 +83,5 @@ func (us *undistortSource) Read(ctx context.Context) (image.Image, func(), error // Close closes the original stream. func (us *undistortSource) Close(ctx context.Context) error { - return us.originalStream.Close(ctx) + return us.originalSource.Close(ctx) } diff --git a/components/camera/transformpipeline/undistort_test.go b/components/camera/transformpipeline/undistort_test.go index 41f6184bd84..45809b5ff97 100644 --- a/components/camera/transformpipeline/undistort_test.go +++ b/components/camera/transformpipeline/undistort_test.go @@ -5,13 +5,11 @@ import ( "errors" "testing" - "github.com/pion/mediadevices/pkg/prop" "go.viam.com/test" "go.viam.com/utils/artifact" "go.viam.com/rdk/components/camera" "go.viam.com/rdk/components/camera/fake" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/utils" @@ -38,7 +36,8 @@ var undistortTestBC = &transform.BrownConrady{ func TestUndistortSetup(t *testing.T) { img, err := rimage.NewImageFromFile(artifact.MustPath("rimage/board1_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) // no camera parameters am := utils.AttributeMap{} @@ -48,11 +47,12 @@ func TestUndistortSetup(t *testing.T) { test.That(t, source.Close(context.Background()), test.ShouldBeNil) // bad stream type - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) am = utils.AttributeMap{"intrinsic_parameters": undistortTestParams, "distortion_parameters": undistortTestBC} us, _, err := newUndistortTransform(context.Background(), source, camera.ImageType("fake"), am) test.That(t, err, test.ShouldBeNil) - _, _, err = camera.ReadImage(context.Background(), us) + _, _, err = us.GetImage(context.Background()) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "do not know how to decode stream") test.That(t, us.Close(context.Background()), test.ShouldBeNil) @@ -61,7 +61,7 @@ func TestUndistortSetup(t *testing.T) { us, stream, err := newUndistortTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - _, _, err = camera.ReadImage(context.Background(), us) + _, _, err = us.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, us.Close(context.Background()), test.ShouldBeNil) @@ -71,20 +71,21 @@ func TestUndistortSetup(t *testing.T) { func TestUndistortImage(t *testing.T) { img, err := rimage.NewImageFromFile(artifact.MustPath("rimage/board1_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) // success am := utils.AttributeMap{"intrinsic_parameters": undistortTestParams, "distortion_parameters": undistortTestBC} us, stream, err := newUndistortTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - corrected, _, err := camera.ReadImage(context.Background(), us) + corrected, _, err := us.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) result, ok := corrected.(*rimage.Image) test.That(t, ok, test.ShouldEqual, true) test.That(t, us.Close(context.Background()), test.ShouldBeNil) - sourceImg, _, err := camera.ReadImage(context.Background(), source) + sourceImg, _, err := source.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) expected, ok := sourceImg.(*rimage.Image) test.That(t, ok, test.ShouldEqual, true) @@ -92,11 +93,17 @@ func TestUndistortImage(t *testing.T) { test.That(t, result, test.ShouldResemble, expected) // bad source - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: rimage.NewImage(10, 10)}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader( + context.Background(), + &fake.StaticSource{ColorImg: rimage.NewImage(10, 10)}, + nil, + camera.UnspecifiedStream, + ) + test.That(t, err, test.ShouldBeNil) us, stream, err = newUndistortTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - _, _, err = camera.ReadImage(context.Background(), us) + _, _, err = us.GetImage(context.Background()) test.That(t, err.Error(), test.ShouldContainSubstring, "img dimension and intrinsics don't match") test.That(t, us.Close(context.Background()), test.ShouldBeNil) } @@ -105,20 +112,21 @@ func TestUndistortDepthMap(t *testing.T) { img, err := rimage.NewDepthMapFromFile( context.Background(), artifact.MustPath("rimage/board1_gray_small.png")) test.That(t, err, test.ShouldBeNil) - source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: img}, prop.Video{}) + source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: img}, nil, camera.UnspecifiedStream) + test.That(t, err, test.ShouldBeNil) // success am := utils.AttributeMap{"intrinsic_parameters": undistortTestParams, "distortion_parameters": undistortTestBC} us, stream, err := newUndistortTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - corrected, _, err := camera.ReadImage(context.Background(), us) + corrected, _, err := us.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) result, ok := corrected.(*rimage.DepthMap) test.That(t, ok, test.ShouldEqual, true) test.That(t, us.Close(context.Background()), test.ShouldBeNil) - sourceImg, _, err := camera.ReadImage(context.Background(), source) + sourceImg, _, err := source.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) expected, ok := sourceImg.(*rimage.DepthMap) test.That(t, ok, test.ShouldEqual, true) @@ -126,20 +134,32 @@ func TestUndistortDepthMap(t *testing.T) { test.That(t, result, test.ShouldResemble, expected) // bad source - source = gostream.NewVideoSource(&fake.StaticSource{DepthImg: rimage.NewEmptyDepthMap(10, 10)}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader( + context.Background(), + &fake.StaticSource{DepthImg: rimage.NewEmptyDepthMap(10, 10)}, + nil, + camera.UnspecifiedStream, + ) + test.That(t, err, test.ShouldBeNil) us, stream, err = newUndistortTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - _, _, err = camera.ReadImage(context.Background(), us) + _, _, err = us.GetImage(context.Background()) test.That(t, err.Error(), test.ShouldContainSubstring, "img dimension and intrinsics don't match") test.That(t, us.Close(context.Background()), test.ShouldBeNil) // can't convert image to depth map - source = gostream.NewVideoSource(&fake.StaticSource{ColorImg: rimage.NewImage(10, 10)}, prop.Video{}) + source, err = camera.NewVideoSourceFromReader( + context.Background(), + &fake.StaticSource{ColorImg: rimage.NewImage(10, 10)}, + nil, + camera.UnspecifiedStream, + ) + test.That(t, err, test.ShouldBeNil) us, stream, err = newUndistortTransform(context.Background(), source, camera.DepthStream, am) test.That(t, stream, test.ShouldEqual, camera.DepthStream) test.That(t, err, test.ShouldBeNil) - _, _, err = camera.ReadImage(context.Background(), us) + _, _, err = us.GetImage(context.Background()) test.That(t, err.Error(), test.ShouldContainSubstring, "don't know how to make DepthMap") test.That(t, us.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/videosource/webcam.go b/components/camera/videosource/webcam.go index 66cf37f68fe..2597b254206 100644 --- a/components/camera/videosource/webcam.go +++ b/components/camera/videosource/webcam.go @@ -565,6 +565,10 @@ func (c *monitoredWebcam) Stream(ctx context.Context, errHandlers ...gostream.Er return c.exposedSwapper.Stream(ctx, errHandlers...) } +func (c *monitoredWebcam) GetImage(ctx context.Context) (image.Image, func(), error) { + return gostream.ReadImage(ctx, c.underlyingSource) +} + func (c *monitoredWebcam) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { c.mu.RLock() defer c.mu.RUnlock() diff --git a/components/camera/videosourcewrappers.go b/components/camera/videosourcewrappers.go index db41e934324..f8af8ca2fb7 100644 --- a/components/camera/videosourcewrappers.go +++ b/components/camera/videosourcewrappers.go @@ -2,6 +2,7 @@ package camera import ( "context" + "image" "time" "github.com/pion/mediadevices/pkg/prop" @@ -197,6 +198,10 @@ func (vs *videoSource) Stream(ctx context.Context, errHandlers ...gostream.Error return vs.videoSource.Stream(ctx, errHandlers...) } +func (vs *videoSource) GetImage(ctx context.Context) (image.Image, func(), error) { + return ReadImage(ctx, vs.videoSource) +} + // Images is for getting simultaneous images from different sensors // If the underlying source did not specify an Images function, a default is applied. // The default returns a list of 1 image from ReadImage, and the current time. diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 776900d379a..0d2dfe9ab6c 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -334,13 +334,11 @@ func TestStatusClient(t *testing.T) { var imageReleased bool var imageReleasedMu sync.Mutex - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return img, func() {}, nil - })), nil + injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { + imageReleasedMu.Lock() + imageReleased = true + imageReleasedMu.Unlock() + return img, func() {}, nil } injectInputDev := &inject.InputController{} @@ -512,7 +510,7 @@ func TestStatusClient(t *testing.T) { camera1, err := camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - _, _, err = camera.ReadImage(context.Background(), camera1) + _, _, err = camera1.GetImage(context.Background()) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "not found") @@ -591,7 +589,7 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA) - frame, _, err := camera.ReadImage(ctx, camera1) + frame, _, err := camera1.GetImage(ctx) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index b8acda30b62..76f8f475f4d 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -93,7 +93,7 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - pic, _, err := camera.ReadImage(context.Background(), c1) + pic, _, err := c1.GetImage(context.Background()) test.That(t, err, test.ShouldBeNil) bounds := pic.Bounds() diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index 844b8772095..ad3464dac29 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -24,7 +24,6 @@ import ( "go.viam.com/rdk/components/arm" "go.viam.com/rdk/components/camera" "go.viam.com/rdk/data" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" datasync "go.viam.com/rdk/services/datamanager/builtin/sync" @@ -154,11 +153,10 @@ func TestSyncEnabled(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - StreamFunc: func( + GetImageFunc: func( ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.VideoStream, error) { - return newVideoStream(imgPng), nil + ) (image.Image, func(), error) { + return imgPng, func() {}, nil }, }, }) @@ -356,11 +354,10 @@ func TestDataCaptureUploadIntegration(t *testing.T) { } else { r = setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - StreamFunc: func( + GetImageFunc: func( ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.VideoStream, error) { - return newVideoStream(imgPng), nil + ) (image.Image, func(), error) { + return imgPng, func() {}, nil }, }, }) @@ -758,11 +755,10 @@ func TestStreamingDCUpload(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(nil, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - StreamFunc: func( + GetImageFunc: func( ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.VideoStream, error) { - return newVideoStream(imgPng), nil + ) (image.Image, func(), error) { + return imgPng, func() {}, nil }, }, }) @@ -998,11 +994,10 @@ func TestSyncConfigUpdateBehavior(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(nil, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - StreamFunc: func( + GetImageFunc: func( ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.VideoStream, error) { - return newVideoStream(imgPng), nil + ) (image.Image, func(), error) { + return imgPng, func() {}, nil }, }, }) @@ -1156,14 +1151,6 @@ func populateFileContents(fileContents []byte) []byte { return fileContents } -func newVideoStream(imgPng image.Image) gostream.VideoStream { - return gostream.NewEmbeddedVideoStreamFromReader( - gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - return imgPng, func() {}, nil - }), - ) -} - func newImgPng(t *testing.T) image.Image { img := image.NewNRGBA(image.Rect(0, 0, 4, 4)) var imgBuf bytes.Buffer diff --git a/services/datamanager/builtin/builtin_test.go b/services/datamanager/builtin/builtin_test.go index ba1c59848c7..dc386da0ff1 100644 --- a/services/datamanager/builtin/builtin_test.go +++ b/services/datamanager/builtin/builtin_test.go @@ -3,6 +3,7 @@ package builtin import ( "cmp" "context" + "image" "io/fs" "maps" "math" @@ -29,7 +30,6 @@ import ( "go.viam.com/rdk/components/sensor" "go.viam.com/rdk/config" "go.viam.com/rdk/data" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/internal/cloud" cloudinject "go.viam.com/rdk/internal/testutils/inject" "go.viam.com/rdk/logging" @@ -446,11 +446,10 @@ func TestSync(t *testing.T) { if tc.dataType == v1.DataType_DATA_TYPE_BINARY_SENSOR { r = setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - StreamFunc: func( + GetImageFunc: func( ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.VideoStream, error) { - return newVideoStream(imgPng), nil + ) (image.Image, func(), error) { + return imgPng, func() {}, nil }, }, }) diff --git a/services/vision/obstaclesdepth/obstacles_depth.go b/services/vision/obstaclesdepth/obstacles_depth.go index ed450b98d9b..6c68108e5d3 100644 --- a/services/vision/obstaclesdepth/obstacles_depth.go +++ b/services/vision/obstaclesdepth/obstacles_depth.go @@ -117,7 +117,7 @@ func (o *obsDepth) buildObsDepth(logger logging.Logger) func( // buildObsDepthNoIntrinsics will return the median depth in the depth map as a Geometry point. func (o *obsDepth) obsDepthNoIntrinsics(ctx context.Context, src camera.VideoSource) ([]*vision.Object, error) { - pic, release, err := camera.ReadImage(ctx, src) + pic, release, err := src.GetImage(ctx) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } @@ -149,7 +149,7 @@ func (o *obsDepth) obsDepthWithIntrinsics(ctx context.Context, src camera.VideoS if o.intrinsics == nil { return nil, errors.New("tried to build obstacles depth with intrinsics but no instrinsics found") } - pic, release, err := camera.ReadImage(ctx, src) + pic, release, err := src.GetImage(ctx) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } diff --git a/services/vision/vision.go b/services/vision/vision.go index 58118aa0625..bde6e35ed67 100644 --- a/services/vision/vision.go +++ b/services/vision/vision.go @@ -271,7 +271,7 @@ func (vm *vizModel) DetectionsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, release, err := camera.ReadImage(ctx, cam) + img, release, err := cam.GetImage(ctx) if err != nil { return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } @@ -314,7 +314,7 @@ func (vm *vizModel) ClassificationsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, release, err := camera.ReadImage(ctx, cam) + img, release, err := cam.GetImage(ctx) if err != nil { return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } @@ -364,7 +364,7 @@ func (vm *vizModel) CaptureAllFromCamera( if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, release, err := camera.ReadImage(ctx, cam) + img, release, err := cam.GetImage(ctx) if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not get image from %s", cameraName) } diff --git a/testutils/inject/camera.go b/testutils/inject/camera.go index f58e4a26651..c975e18d0c0 100644 --- a/testutils/inject/camera.go +++ b/testutils/inject/camera.go @@ -2,12 +2,12 @@ package inject import ( "context" + "image" "github.com/pkg/errors" "go.viam.com/rdk/components/camera" "go.viam.com/rdk/components/camera/rtppassthrough" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage/transform" @@ -20,14 +20,11 @@ type Camera struct { RTPPassthroughSource rtppassthrough.Source DoFunc func(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error) ImagesFunc func(ctx context.Context) ([]camera.NamedImage, resource.ResponseMetadata, error) - StreamFunc func( - ctx context.Context, - errHandlers ...gostream.ErrorHandler, - ) (gostream.VideoStream, error) - NextPointCloudFunc func(ctx context.Context) (pointcloud.PointCloud, error) - ProjectorFunc func(ctx context.Context) (transform.Projector, error) - PropertiesFunc func(ctx context.Context) (camera.Properties, error) - CloseFunc func(ctx context.Context) error + GetImageFunc func(ctx context.Context) (image.Image, func(), error) + NextPointCloudFunc func(ctx context.Context) (pointcloud.PointCloud, error) + ProjectorFunc func(ctx context.Context) (transform.Projector, error) + PropertiesFunc func(ctx context.Context) (camera.Properties, error) + CloseFunc func(ctx context.Context) error } // NewCamera returns a new injected camera. @@ -51,18 +48,15 @@ func (c *Camera) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, err return nil, errors.New("NextPointCloud unimplemented") } -// Stream calls the injected Stream or the real version. -func (c *Camera) Stream( - ctx context.Context, - errHandlers ...gostream.ErrorHandler, -) (gostream.VideoStream, error) { - if c.StreamFunc != nil { - return c.StreamFunc(ctx, errHandlers...) +// GetImage calls the injected GetImage or the real version. +func (c *Camera) GetImage(ctx context.Context) (image.Image, func(), error) { + if c.GetImageFunc != nil { + return c.GetImageFunc(ctx) } if c.Camera != nil { - return c.Camera.Stream(ctx, errHandlers...) + return c.Camera.GetImage(ctx) } - return nil, errors.Wrap(ctx.Err(), "no stream function available") + return nil, func() {}, errors.Wrap(ctx.Err(), "no GetImage function available") } // Properties calls the injected Properties or the real version. From 41cb592ee7aa8172497385c57325c955306ce74c Mon Sep 17 00:00:00 2001 From: hexbabe Date: Fri, 25 Oct 2024 13:41:06 -0400 Subject: [PATCH 02/51] Use camera pkg scoped ReadImage in webcam --- components/camera/videosource/webcam.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/components/camera/videosource/webcam.go b/components/camera/videosource/webcam.go index 2597b254206..e578cf42d57 100644 --- a/components/camera/videosource/webcam.go +++ b/components/camera/videosource/webcam.go @@ -566,7 +566,7 @@ func (c *monitoredWebcam) Stream(ctx context.Context, errHandlers ...gostream.Er } func (c *monitoredWebcam) GetImage(ctx context.Context) (image.Image, func(), error) { - return gostream.ReadImage(ctx, c.underlyingSource) + return camera.ReadImage(ctx, c.underlyingSource) } func (c *monitoredWebcam) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { From d6439dd29e1933aaffc6ed2c2cf49095cd9f6315 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 6 Nov 2024 12:21:47 -0500 Subject: [PATCH 03/51] Use agreed upon Image signature --- components/camera/camera.go | 7 +- components/camera/camera_test.go | 20 +-- components/camera/client.go | 96 +++++-------- components/camera/client_test.go | 119 ++++++++-------- components/camera/collector.go | 14 +- components/camera/extra.go | 2 +- components/camera/fake/camera_test.go | 6 +- components/camera/fake/image_file_test.go | 29 ++-- components/camera/ffmpeg/ffmpeg_test.go | 3 +- components/camera/replaypcd/replaypcd.go | 14 +- components/camera/server.go | 50 ++++--- components/camera/server_test.go | 132 +++++------------- .../camera/transformpipeline/classifier.go | 2 +- .../transformpipeline/classifier_test.go | 2 +- .../camera/transformpipeline/composed.go | 4 +- .../camera/transformpipeline/composed_test.go | 17 ++- .../camera/transformpipeline/depth_edges.go | 2 +- .../transformpipeline/depth_edges_test.go | 8 +- .../camera/transformpipeline/detector.go | 2 +- .../camera/transformpipeline/detector_test.go | 4 +- components/camera/transformpipeline/mods.go | 6 +- .../camera/transformpipeline/mods_test.go | 50 +++---- .../camera/transformpipeline/pipeline.go | 4 +- .../camera/transformpipeline/pipeline_test.go | 18 +-- .../camera/transformpipeline/preprocessing.go | 2 +- .../camera/transformpipeline/segmenter.go | 2 +- .../transformpipeline/segmenter_test.go | 12 ++ .../camera/transformpipeline/undistort.go | 2 +- .../transformpipeline/undistort_test.go | 18 +-- components/camera/videosource/webcam.go | 14 +- components/camera/videosourcewrappers.go | 14 +- robot/client/client.go | 1 - robot/client/client_test.go | 28 ++-- robot/impl/local_robot_test.go | 5 +- robot/server/server_test.go | 11 +- robot/web/web_test.go | 11 +- .../datamanager/builtin/builtin_sync_test.go | 51 +++++-- services/datamanager/builtin/builtin_test.go | 14 +- services/sensors/server_test.go | 15 +- .../vision/obstaclesdepth/obstacles_depth.go | 23 ++- services/vision/vision.go | 24 +++- testutils/inject/camera.go | 44 ++++-- 42 files changed, 449 insertions(+), 453 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 6ff8b979045..81052b4da2e 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -111,6 +111,10 @@ type Camera interface { // // [camera component docs]: https://docs.viam.com/components/camera/ type VideoSource interface { + // Image returns a byte slice representing an image that tries to adhere to the MIME type hint. + // Image also may return a string representing the mime type hint or empty string if not. + Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) + // Images is used for getting simultaneous images from different imagers, // along with associated metadata (just timestamp for now). It's not for getting a time series of images from the same imager. Images(ctx context.Context) ([]NamedImage, resource.ResponseMetadata, error) @@ -119,9 +123,6 @@ type VideoSource interface { // that may have a MIME type hint dictated in the context via gostream.WithMIMETypeHint. Stream(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) - // GetImage returns a single image that may have a MIME type hint dictated in the context via gostream.WithMIMETypeHint. - GetImage(ctx context.Context) (image.Image, func(), error) - // NextPointCloud returns the next immediately available point cloud, not necessarily one // a part of a sequence. In the future, there could be streaming of point clouds. NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index 035fcf5817d..d4c8bd2b5d7 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -10,7 +10,6 @@ import ( "go.viam.com/utils/artifact" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -183,13 +182,13 @@ func TestCameraWithNoProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, _, err := noProj2.GetImage(gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG))) + imgBytes, mimeType, err := noProj2.Image(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil) test.That(t, err, test.ShouldBeNil) - - depthImg := img.(*rimage.DepthMap) + img, err := rimage.DecodeImage(context.Background(), imgBytes, mimeType) test.That(t, err, test.ShouldBeNil) - test.That(t, depthImg.Bounds().Dx(), test.ShouldEqual, 1280) - test.That(t, depthImg.Bounds().Dy(), test.ShouldEqual, 720) + + test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) + test.That(t, img.Bounds().Dy(), test.ShouldEqual, 720) test.That(t, noProj2.Close(context.Background()), test.ShouldBeNil) } @@ -232,13 +231,14 @@ func TestCameraWithProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, _, err := cam2.GetImage(gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG)) + imgBytes, mimeType, err := cam2.Image(context.Background(), rutils.MimeTypePNG, nil) + test.That(t, err, test.ShouldBeNil) + img, err := rimage.DecodeImage(context.Background(), imgBytes, mimeType) test.That(t, err, test.ShouldBeNil) - depthImg := img.(*rimage.DepthMap) test.That(t, err, test.ShouldBeNil) - test.That(t, depthImg.Bounds().Dx(), test.ShouldEqual, 1280) - test.That(t, depthImg.Bounds().Dy(), test.ShouldEqual, 720) + test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) + test.That(t, img.Bounds().Dy(), test.ShouldEqual, 720) // cam2 should implement a default GetImages, that just returns the one image images, _, err := cam2.Images(context.Background()) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/client.go b/components/camera/client.go index aeb6826f9a4..b5081575f5a 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -21,8 +21,6 @@ import ( goprotoutils "go.viam.com/utils/protoutils" "go.viam.com/utils/rpc" "golang.org/x/exp/slices" - "google.golang.org/protobuf/proto" - "google.golang.org/protobuf/types/known/structpb" "go.viam.com/rdk/components/camera/rtppassthrough" "go.viam.com/rdk/data" @@ -100,60 +98,6 @@ func NewClientFromConn( }, nil } -func getExtra(ctx context.Context) (*structpb.Struct, error) { - ext := &structpb.Struct{} - if extra, ok := FromContext(ctx); ok { - var err error - if ext, err = goprotoutils.StructToStructPb(extra); err != nil { - return nil, err - } - } - - dataExt, err := data.GetExtraFromContext(ctx) - if err != nil { - return nil, err - } - - proto.Merge(ext, dataExt) - return ext, nil -} - -// RSDK-8663: This method signature is depended on by the `camera.serviceServer` optimization that -// avoids using an image stream just to get a single image. -func (c *client) Read(ctx context.Context) (image.Image, func(), error) { - ctx, span := trace.StartSpan(ctx, "camera::client::Read") - defer span.End() - mimeType := gostream.MIMETypeHint(ctx, "") - expectedType, _ := utils.CheckLazyMIMEType(mimeType) - - ext, err := getExtra(ctx) - if err != nil { - return nil, nil, err - } - - resp, err := c.client.GetImage(ctx, &pb.GetImageRequest{ - Name: c.name, - MimeType: expectedType, - Extra: ext, - }) - if err != nil { - return nil, nil, err - } - - if expectedType != "" && resp.MimeType != expectedType { - c.logger.CDebugw(ctx, "got different MIME type than what was asked for", "sent", expectedType, "received", resp.MimeType) - } else { - resp.MimeType = mimeType - } - - resp.MimeType = utils.WithLazyMIMEType(resp.MimeType) - img, err := rimage.DecodeImage(ctx, resp.Image, resp.MimeType) - if err != nil { - return nil, nil, err - } - return img, func() {}, nil -} - func (c *client) Stream( ctx context.Context, errHandlers ...gostream.ErrorHandler, @@ -201,13 +145,19 @@ func (c *client) Stream( return } - frame, release, err := c.Read(streamCtx) + frame, mimeType, err := c.Image(streamCtx, gostream.MIMETypeHint(ctx, ""), nil) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) } } + img, err := rimage.DecodeImage(ctx, frame, mimeType) + if err != nil { + c.logger.CWarnw(ctx, "error decoding image", "err", err) + return + } + select { case <-streamCtx.Done(): return @@ -217,8 +167,8 @@ func (c *client) Stream( } return case frameCh <- gostream.MediaReleasePairWithError[image.Image]{ - Media: frame, - Release: release, + Media: img, + Release: func() {}, Err: err, }: } @@ -228,8 +178,32 @@ func (c *client) Stream( return stream, nil } -func (c *client) GetImage(ctx context.Context) (image.Image, func(), error) { - return c.Read(ctx) +func (c *client) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + ctx, span := trace.StartSpan(ctx, "camera::client::GetImage") + defer span.End() + expectedType, _ := utils.CheckLazyMIMEType(mimeType) + + structExtra, err := goprotoutils.StructToStructPb(extra) + if err != nil { + return nil, "", err + } + resp, err := c.client.GetImage(ctx, &pb.GetImageRequest{ + Name: c.name, + MimeType: expectedType, + Extra: structExtra, + }) + if err != nil { + return nil, "", err + } + + if expectedType != "" && resp.MimeType != expectedType { + c.logger.CDebugw(ctx, "got different MIME type than what was asked for", "sent", expectedType, "received", resp.MimeType) + } else { + resp.MimeType = mimeType + } + + mimeType = utils.WithLazyMIMEType(resp.MimeType) + return resp.Image, mimeType, nil } func (c *client) Images(ctx context.Context) ([]NamedImage, resource.ResponseMetadata, error) { diff --git a/components/camera/client_test.go b/components/camera/client_test.go index a0cd0f39dfc..b5ee5a8542b 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -7,7 +7,6 @@ import ( "image/color" "image/png" "net" - "sync" "testing" "time" @@ -72,8 +71,6 @@ func TestClient(t *testing.T) { } projA = intrinsics - var imageReleased bool - var imageReleasedMu sync.Mutex // color camera injectCamera.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { return pcA, nil @@ -99,11 +96,10 @@ func TestClient(t *testing.T) { ts := time.UnixMilli(12345) return images, resource.ResponseMetadata{CapturedAt: ts}, nil } - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return imgPng, func() {}, nil + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + test.That(t, err, test.ShouldBeNil) + return resBytes, mimeType, nil } // depth camera injectCameraDepth := &inject.Camera{} @@ -125,11 +121,10 @@ func TestClient(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return depthImg, func() {}, nil + injectCameraDepth.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + resBytes, err := rimage.EncodeImage(ctx, depthImg, mimeType) + test.That(t, err, test.ShouldBeNil) + return resBytes, mimeType, nil } // bad camera injectCamera2 := &inject.Camera{} @@ -142,8 +137,8 @@ func TestClient(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - return nil, func() {}, errGetImageFailed + injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + return nil, mimeType, errGetImageFailed } resources := map[resource.Name]camera.Camera{ @@ -176,15 +171,13 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA) - frame, _, err := camera1Client.GetImage(ctx) + frameBytes, mimeType, err := camera1Client.Image(context.Background(), rutils.MimeTypeRawRGBA, nil) + test.That(t, err, test.ShouldBeNil) + frame, err := rimage.DecodeImage(context.Background(), frameBytes, mimeType) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() pcB, err := camera1Client.NextPointCloud(context.Background()) test.That(t, err, test.ShouldBeNil) @@ -226,16 +219,14 @@ func TestClient(t *testing.T) { client, err := resourceAPI.RPCClient(context.Background(), conn, "", camera.Named(depthCameraName), logger) test.That(t, err, test.ShouldBeNil) - ctx := gostream.WithMIMETypeHint( - context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)) - frame, _, err := client.GetImage(ctx) + ctx := context.Background() + frameBytes, mimeType, err := client.Image(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil) + test.That(t, err, test.ShouldBeNil) + frame, err := rimage.DecodeImage(context.Background(), frameBytes, mimeType) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) test.That(t, dm, test.ShouldResemble, depthImg) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, client.Close(context.Background()), test.ShouldBeNil) test.That(t, conn.Close(), test.ShouldBeNil) @@ -247,7 +238,7 @@ func TestClient(t *testing.T) { client2, err := resourceAPI.RPCClient(context.Background(), conn, "", camera.Named(failCameraName), logger) test.That(t, err, test.ShouldBeNil) - _, _, err = client2.GetImage(context.Background()) + _, _, err = client2.Image(context.Background(), "", nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) @@ -268,61 +259,50 @@ func TestClient(t *testing.T) { camClient, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, extra, test.ShouldBeEmpty) - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } ctx := context.Background() - _, _, err = camClient.GetImage(ctx) + _, _, err = camClient.Image(ctx, "", nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra["hello"], test.ShouldEqual, "world") - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } - // one kvp created with camera.Extra - ext := camera.Extra{"hello": "world"} - ctx = camera.NewContext(ctx, ext) - _, _, err = camClient.GetImage(ctx) + // one kvp created with map[string]interface{} + ext := map[string]interface{}{"hello": "world"} + _, _, err = camClient.Image(ctx, "", ext) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } - // one kvp created with data.FromDMContextKey - ctx = context.WithValue(context.Background(), data.FromDMContextKey{}, true) - _, _, err = camClient.GetImage(ctx) + _, _, err = camClient.Image(context.Background(), "", map[string]interface{}{data.FromDMString: true}) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, len(extra), test.ShouldEqual, 2) test.That(t, extra["hello"], test.ShouldEqual, "world") test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } // merge values from data and camera - ext = camera.Extra{"hello": "world"} - ctx = camera.NewContext(ctx, ext) - _, _, err = camClient.GetImage(ctx) + ext = map[string]interface{}{"hello": "world", data.FromDMString: true} + ctx = context.Background() + _, _, err = camClient.Image(ctx, "", ext) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) @@ -449,13 +429,18 @@ func TestClientLazyImage(t *testing.T) { imgPng, err := png.Decode(bytes.NewReader(imgBuf.Bytes())) test.That(t, err, test.ShouldBeNil) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - mimeType, _ := rutils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, rutils.MimeTypeRawRGBA)) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + if mimeType == "" { + mimeType = rutils.MimeTypeRawRGBA + } + mimeType, _ = rutils.CheckLazyMIMEType(mimeType) switch mimeType { case rutils.MimeTypePNG: - return imgPng, func() {}, nil + resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + test.That(t, err, test.ShouldBeNil) + return resBytes, mimeType, nil default: - return nil, nil, errInvalidMimeType + return nil, mimeType, errInvalidMimeType } } @@ -477,16 +462,20 @@ func TestClientLazyImage(t *testing.T) { camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG) - frame, _, err := camera1Client.GetImage(ctx) + ctx := context.Background() + frameBytes, mimeType, err := camera1Client.Image(ctx, rutils.MimeTypePNG, nil) + test.That(t, err, test.ShouldBeNil) + frame, err := rimage.DecodeImage(ctx, frameBytes, mimeType) test.That(t, err, test.ShouldBeNil) // Should always lazily decode test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) frameLazy := frame.(*rimage.LazyEncodedImage) test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) - ctx = gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)) - frame, _, err = camera1Client.GetImage(ctx) + ctx = context.Background() + frameBytes, mimeType, err = camera1Client.Image(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil) + test.That(t, err, test.ShouldBeNil) + frame, err = rimage.DecodeImage(ctx, frameBytes, mimeType) test.That(t, err, test.ShouldBeNil) test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) frameLazy = frame.(*rimage.LazyEncodedImage) @@ -576,8 +565,10 @@ func TestClientStreamAfterClose(t *testing.T) { injectCamera.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - return img, func() {}, nil + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) + test.That(t, err, test.ShouldBeNil) + return imgBytes, mimeType, nil } // Register CameraService API in our gRPC server. diff --git a/components/camera/collector.go b/components/camera/collector.go index 7b922f8a700..d52fbdae2b4 100644 --- a/components/camera/collector.go +++ b/components/camera/collector.go @@ -12,7 +12,6 @@ import ( "go.viam.com/rdk/data" "go.viam.com/rdk/pointcloud" - "go.viam.com/rdk/rimage" "go.viam.com/rdk/utils" ) @@ -96,7 +95,7 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d ctx = context.WithValue(ctx, data.FromDMContextKey{}, true) - img, release, err := camera.GetImage(ctx) + img, _, err := camera.Image(ctx, mimeType.String(), Extra{}) if err != nil { // A modular filter component can be created to filter the readings from a component. The error ErrNoCaptureToStore // is used in the datamanager to exclude readings from being captured and stored. @@ -106,22 +105,13 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d return nil, data.FailedToReadErr(params.ComponentName, readImage.String(), err) } - defer func() { - if release != nil { - release() - } - }() mimeStr := new(wrapperspb.StringValue) if err := mimeType.UnmarshalTo(mimeStr); err != nil { return nil, err } - outBytes, err := rimage.EncodeImage(ctx, img, mimeStr.Value) - if err != nil { - return nil, err - } - return outBytes, nil + return img, nil }) return data.NewCollector(cFunc, params) } diff --git a/components/camera/extra.go b/components/camera/extra.go index 35dd04fbfb9..b3e80316a94 100644 --- a/components/camera/extra.go +++ b/components/camera/extra.go @@ -2,7 +2,7 @@ package camera import "context" -// Extra is the type of value stored in the Contexts. +// Extra is the type used to represent the extra param for camera methods. type ( Extra map[string]interface{} key int diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index b58cfbbcc5f..e9536fc853c 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -15,6 +15,8 @@ import ( "go.viam.com/rdk/components/camera/rtppassthrough" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" + "go.viam.com/rdk/utils" ) func TestFakeCameraParams(t *testing.T) { @@ -93,7 +95,9 @@ func TestRTPPassthrough(t *testing.T) { camera, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) - img, _, err := camera.GetImage(context.Background()) + imgBytes, mimeType, err := camera.Image(context.Background(), utils.MimeTypeRawRGBA, nil) + test.That(t, err, test.ShouldBeNil) + img, err := rimage.DecodeImage(context.Background(), imgBytes, mimeType) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index b0b0c41037b..d22cb7c919b 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -16,6 +16,7 @@ import ( "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" + "go.viam.com/rdk/utils" ) func TestPCD(t *testing.T) { @@ -45,10 +46,11 @@ func TestPCD(t *testing.T) { readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) - strmImg, _, err := cam.GetImage(ctx) + imgBytes, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldBeNil) - test.That(t, strmImg, test.ShouldResemble, readInImage) - test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds()) + expectedBytes, err := rimage.EncodeImage(ctx, readInImage, utils.MimeTypeJPEG) + test.That(t, err, test.ShouldBeNil) + test.That(t, imgBytes, test.ShouldResemble, expectedBytes) err = cam.Close(ctx) test.That(t, err, test.ShouldBeNil) @@ -68,10 +70,11 @@ func TestColor(t *testing.T) { readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) - strmImg, _, err := cam.GetImage(ctx) + imgBytes, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) + test.That(t, err, test.ShouldBeNil) + expectedBytes, err := rimage.EncodeImage(ctx, readInImage, utils.MimeTypeJPEG) test.That(t, err, test.ShouldBeNil) - test.That(t, strmImg, test.ShouldResemble, readInImage) - test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds()) + test.That(t, imgBytes, test.ShouldResemble, expectedBytes) err = cam.Close(ctx) test.That(t, err, test.ShouldBeNil) @@ -82,13 +85,13 @@ func TestColorOddResolution(t *testing.T) { imgFile, err := os.Create(imgFilePath) test.That(t, err, test.ShouldBeNil) - img := image.NewRGBA(image.Rect(0, 0, 3, 3)) + img := image.NewNRGBA(image.Rect(0, 0, 3, 3)) for x := 0; x < img.Bounds().Dx(); x++ { for y := 0; y < img.Bounds().Dy(); y++ { img.Set(x, y, color.White) } } - err = jpeg.Encode(imgFile, img, nil) + err = jpeg.Encode(imgFile, img, &jpeg.Options{Quality: 75}) test.That(t, err, test.ShouldBeNil) err = imgFile.Close() test.That(t, err, test.ShouldBeNil) @@ -99,15 +102,17 @@ func TestColorOddResolution(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - readInImage, err := rimage.NewImageFromFile(imgFilePath) + imgBytes, _, err := cam.Image(ctx, utils.MimeTypeRawRGBA, nil) test.That(t, err, test.ShouldBeNil) - strmImg, _, err := cam.GetImage(ctx) + strmImg, err := rimage.DecodeImage(ctx, imgBytes, utils.MimeTypeRawRGBA) test.That(t, err, test.ShouldBeNil) - expectedBounds := image.Rect(0, 0, readInImage.Bounds().Dx()-1, readInImage.Bounds().Dy()-1) - test.That(t, strmImg, test.ShouldResemble, readInImage.SubImage(expectedBounds)) + expectedBounds := image.Rect(0, 0, img.Bounds().Dx()-1, img.Bounds().Dy()-1) test.That(t, strmImg.Bounds(), test.ShouldResemble, expectedBounds) + val, _, err := rimage.CompareImages(strmImg, img.SubImage(expectedBounds)) + test.That(t, err, test.ShouldBeNil) + test.That(t, val, test.ShouldBeLessThanOrEqualTo, 0) err = cam.Close(ctx) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/ffmpeg/ffmpeg_test.go b/components/camera/ffmpeg/ffmpeg_test.go index 4c74b1fac94..d03f79e6a0f 100644 --- a/components/camera/ffmpeg/ffmpeg_test.go +++ b/components/camera/ffmpeg/ffmpeg_test.go @@ -9,6 +9,7 @@ import ( "go.viam.com/utils/artifact" "go.viam.com/rdk/logging" + "go.viam.com/rdk/utils" ) func TestFFMPEGCamera(t *testing.T) { @@ -18,7 +19,7 @@ func TestFFMPEGCamera(t *testing.T) { cam, err := NewFFMPEGCamera(ctx, &Config{VideoPath: path}, logger) test.That(t, err, test.ShouldBeNil) for i := 0; i < 5; i++ { - _, _, err := cam.GetImage(ctx) + _, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldBeNil) } test.That(t, cam.Close(context.Background()), test.ShouldBeNil) diff --git a/components/camera/replaypcd/replaypcd.go b/components/camera/replaypcd/replaypcd.go index dcd9c3d8a41..2b00daa5899 100644 --- a/components/camera/replaypcd/replaypcd.go +++ b/components/camera/replaypcd/replaypcd.go @@ -4,7 +4,6 @@ package replaypcd import ( "bytes" "context" - "image" "net/http" "sync" "time" @@ -347,17 +346,8 @@ func (replay *pcdCamera) Stream(ctx context.Context, errHandlers ...gostream.Err return stream, errors.New("Stream is unimplemented") } -func (replay *pcdCamera) GetImage(ctx context.Context) (image.Image, func(), error) { - stream, err := replay.Stream(ctx) - if err != nil { - return nil, func() {}, err - } - defer func() { - if err := stream.Close(ctx); err != nil { - replay.logger.Errorf("stream failed to close: %w", err) - } - }() - return stream.Next(ctx) +func (replay *pcdCamera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + return nil, "", errors.New("Image is unimplemented") } // Close stops replay camera, closes the channels and its connections to the cloud. diff --git a/components/camera/server.go b/components/camera/server.go index b891b2e2506..6d6fc3a8bdb 100644 --- a/components/camera/server.go +++ b/components/camera/server.go @@ -11,7 +11,6 @@ import ( pb "go.viam.com/api/component/camera/v1" "google.golang.org/genproto/googleapis/api/httpbody" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/protoutils" @@ -81,8 +80,7 @@ func (s *serviceServer) GetImage( ext := req.Extra.AsMap() ctx = NewContext(ctx, ext) - var img image.Image - var release func() + resp := pb.GetImageResponse{} switch castedCam := cam.(type) { case ReadImager: // RSDK-8663: If available, call a method that reads exactly one image. The default @@ -91,28 +89,36 @@ func (s *serviceServer) GetImage( // second image from the underlying camera. This is particularly noticeable on camera // clients. Where a second `GetImage` request can be processed/returned over the // network. Just to be discarded. - img, release, err = castedCam.Read(ctx) - default: - img, release, err = cam.GetImage(gostream.WithMIMETypeHint(ctx, req.MimeType)) - } - if err != nil { - return nil, err - } - defer func() { - if release != nil { - release() + // RSDK-9132(sean yu): In addition to what Dan said above, ReadImager is important + // for camera components that rely on the `release` functionality provided by gostream's `Read` + // such as viamrtsp. + // (check that this comment is 100% true before code review then delete this paranthetical statement) + img, release, err := castedCam.Read(ctx) + if err != nil { + return nil, err } - }() + defer func() { + if release != nil { + release() + } + }() - actualMIME, _ := utils.CheckLazyMIMEType(req.MimeType) - resp := pb.GetImageResponse{ - MimeType: actualMIME, - } - outBytes, err := rimage.EncodeImage(ctx, img, req.MimeType) - if err != nil { - return nil, err + actualMIME, _ := utils.CheckLazyMIMEType(req.MimeType) + resp.MimeType = actualMIME + outBytes, err := rimage.EncodeImage(ctx, img, req.MimeType) + if err != nil { + return nil, err + } + resp.Image = outBytes + default: + imgBytes, mimeType, err := cam.Image(ctx, req.MimeType, ext) + if err != nil { + return nil, err + } + actualMIME, _ := utils.CheckLazyMIMEType(mimeType) + resp.MimeType = actualMIME + resp.Image = imgBytes } - resp.Image = outBytes return &resp, nil } diff --git a/components/camera/server_test.go b/components/camera/server_test.go index ee054331669..fb47842bf34 100644 --- a/components/camera/server_test.go +++ b/components/camera/server_test.go @@ -7,7 +7,6 @@ import ( "image" "image/jpeg" "image/png" - "sync" "testing" "time" @@ -17,7 +16,6 @@ import ( "go.viam.com/rdk/components/camera" "go.viam.com/rdk/data" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -83,8 +81,6 @@ func TestServer(t *testing.T) { err = pcA.Set(pointcloud.NewVector(5, 5, 5), nil) test.That(t, err, test.ShouldBeNil) - var imageReleased bool - var imageReleasedMu sync.Mutex injectCamera.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { return pcA, nil } @@ -112,23 +108,30 @@ func TestServer(t *testing.T) { return projA, nil } wooMIME := "image/woohoo" - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - mimeType, _ := utils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, utils.MimeTypeRawRGBA)) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + if mimeType == "" { + mimeType = utils.MimeTypeRawRGBA + } + mimeType, _ = utils.CheckLazyMIMEType(mimeType) + + var respImg image.Image switch mimeType { case "", utils.MimeTypeRawRGBA: - return img, func() {}, nil + respImg = img case utils.MimeTypePNG: - return imgPng, func() {}, nil + respImg = imgPng case utils.MimeTypeJPEG: - return imgJpeg, func() {}, nil + respImg = imgJpeg case "image/woohoo": - return rimage.NewLazyEncodedImage([]byte{1, 2, 3}, mimeType), func() {}, nil + respImg = rimage.NewLazyEncodedImage([]byte{1, 2, 3}, mimeType) default: - return nil, nil, errInvalidMimeType + return nil, "", errInvalidMimeType + } + resBytes, err := rimage.EncodeImage(ctx, respImg, mimeType) + if err != nil { + return nil, "", err } + return resBytes, mimeType, nil } // depth camera depthImage := rimage.NewEmptyDepthMap(10, 20) @@ -153,11 +156,12 @@ func TestServer(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return depthImage, func() {}, nil + injectCameraDepth.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + resBytes, err := rimage.EncodeImage(ctx, depthImage, mimeType) + if err != nil { + return nil, "", err + } + return resBytes, mimeType, nil } // bad camera injectCamera2.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { @@ -169,8 +173,8 @@ func TestServer(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - return nil, func() {}, errGetImageFailed + injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + return nil, "", errGetImageFailed } // does a depth camera transfer its depth image properly @@ -186,9 +190,6 @@ func TestServer(t *testing.T) { &pb.GetImageRequest{Name: testCameraName, MimeType: utils.MimeTypeRawRGBA}, ) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypeRawRGBA) test.That(t, resp.Image[rimage.RawRGBAHeaderLength:], test.ShouldResemble, img.Pix) @@ -198,9 +199,6 @@ func TestServer(t *testing.T) { &pb.GetImageRequest{Name: testCameraName, MimeType: ""}, ) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypeJPEG) test.That(t, resp.Image, test.ShouldNotBeNil) @@ -210,29 +208,17 @@ func TestServer(t *testing.T) { &pb.GetImageRequest{Name: depthCameraName, MimeType: ""}, ) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypeRawDepth) test.That(t, resp.Image, test.ShouldNotBeNil) - imageReleasedMu.Lock() - imageReleased = false - imageReleasedMu.Unlock() resp, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ Name: testCameraName, MimeType: "image/png", }) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypePNG) test.That(t, resp.Image, test.ShouldResemble, imgBuf.Bytes()) - imageReleasedMu.Lock() - imageReleased = false - imageReleasedMu.Unlock() _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ Name: testCameraName, MimeType: "image/who", @@ -241,17 +227,11 @@ func TestServer(t *testing.T) { test.That(t, err.Error(), test.ShouldContainSubstring, errInvalidMimeType.Error()) // depth camera - imageReleasedMu.Lock() - imageReleased = false - imageReleasedMu.Unlock() resp, err = cameraServer.GetImage( context.Background(), &pb.GetImageRequest{Name: depthCameraName, MimeType: utils.MimeTypePNG}, ) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypePNG) test.That(t, resp.Image, test.ShouldNotBeNil) decodedDepth, err := rimage.DecodeImage( @@ -264,17 +244,11 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, dm, test.ShouldResemble, depthImage) - imageReleasedMu.Lock() - imageReleased = false - imageReleasedMu.Unlock() resp, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ Name: depthCameraName, MimeType: "image/png", }) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypePNG) test.That(t, resp.Image, test.ShouldResemble, depthBuf.Bytes()) // bad camera @@ -327,39 +301,23 @@ func TestServer(t *testing.T) { Name: testCameraName, }) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.ContentType, test.ShouldEqual, "image/jpeg") test.That(t, resp.Data, test.ShouldResemble, imgBufJpeg.Bytes()) - imageReleasedMu.Lock() - imageReleased = false - imageReleasedMu.Unlock() resp, err = cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{ Name: testCameraName, MimeType: "image/png", }) test.That(t, err, test.ShouldBeNil) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() test.That(t, resp.ContentType, test.ShouldEqual, "image/png") test.That(t, resp.Data, test.ShouldResemble, imgBuf.Bytes()) - imageReleasedMu.Lock() - imageReleased = false - imageReleasedMu.Unlock() - _, err = cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{ Name: testCameraName, MimeType: "image/who", }) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errInvalidMimeType.Error()) - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() _, err = cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{Name: failCameraName}) test.That(t, err, test.ShouldNotBeNil) @@ -431,11 +389,9 @@ func TestServer(t *testing.T) { }) t.Run("GetImage with extra", func(t *testing.T) { - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, extra, test.ShouldBeEmpty) - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ @@ -445,15 +401,13 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra["hello"], test.ShouldEqual, "world") - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } - ext, err := goprotoutils.StructToStructPb(camera.Extra{"hello": "world"}) + ext, err := goprotoutils.StructToStructPb(map[string]interface{}{"hello": "world"}) test.That(t, err, test.ShouldBeNil) _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ @@ -464,13 +418,11 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } // one kvp created with data.FromDMContextKey @@ -485,13 +437,11 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - extra, ok := camera.FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { test.That(t, len(extra), test.ShouldEqual, 2) test.That(t, extra["hello"], test.ShouldEqual, "world") test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, func() {}, errGetImageFailed + return nil, "", errGetImageFailed } // use values from data and camera @@ -512,17 +462,3 @@ func TestServer(t *testing.T) { test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) }) } - -//nolint -func TestCameraClientIsReadImager(t *testing.T) { - // RSDK-8663: Enforce that a camera client always satisfies the optimized `ReadImager` - // interface. - cameraClient, err := camera.NewClientFromConn(nil, nil, "", resource.Name{}, nil) - test.That(t, err, test.ShouldBeNil) - - if _, isReadImager := cameraClient.(camera.ReadImager); isReadImager { - // Success - } else { - t.Fatalf("Camera client is expected to be a `ReadImager`. Client type: %T", cameraClient) - } -} diff --git a/components/camera/transformpipeline/classifier.go b/components/camera/transformpipeline/classifier.go index 6dc62d6fcfc..1a13cec9e59 100644 --- a/components/camera/transformpipeline/classifier.go +++ b/components/camera/transformpipeline/classifier.go @@ -91,7 +91,7 @@ func (cs *classifierSource) Read(ctx context.Context) (image.Image, func(), erro return nil, nil, errors.Wrap(err, "source_classifier can't find vision service") } // get image from source camera - img, release, err := cs.src.GetImage(ctx) + img, release, err := camera.ReadImage(ctx, cs.src) if err != nil { return nil, nil, errors.Wrap(err, "could not get next source image") } diff --git a/components/camera/transformpipeline/classifier_test.go b/components/camera/transformpipeline/classifier_test.go index 075f0bb1884..7cb212f139a 100644 --- a/components/camera/transformpipeline/classifier_test.go +++ b/components/camera/transformpipeline/classifier_test.go @@ -99,7 +99,7 @@ func TestClassifierSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) defer classifier.Close(ctx) - resImg, _, err := classifier.GetImage(ctx) + resImg, _, err := camera.ReadImage(ctx, classifier) test.That(t, err, test.ShouldBeNil) ovImg := rimage.ConvertImage(resImg) diff --git a/components/camera/transformpipeline/composed.go b/components/camera/transformpipeline/composed.go index d6fe17c71bb..9b9811132f0 100644 --- a/components/camera/transformpipeline/composed.go +++ b/components/camera/transformpipeline/composed.go @@ -68,7 +68,7 @@ func newDepthToPrettyTransform( func (dtp *depthToPretty) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::depthToPretty::Read") defer span.End() - i, release, err := dtp.src.GetImage(ctx) + i, release, err := camera.ReadImage(ctx, dtp.src) if err != nil { return nil, nil, err } @@ -89,7 +89,7 @@ func (dtp *depthToPretty) PointCloud(ctx context.Context) (pointcloud.PointCloud if dtp.cameraModel == nil || dtp.cameraModel.PinholeCameraIntrinsics == nil { return nil, errors.Wrapf(transform.ErrNoIntrinsics, "depthToPretty transform cannot project to pointcloud") } - i, release, err := dtp.src.GetImage(ctx) + i, release, err := camera.ReadImage(ctx, dtp.src) if err != nil { return nil, err } diff --git a/components/camera/transformpipeline/composed_test.go b/components/camera/transformpipeline/composed_test.go index 52dfbcaaf07..bf288cf938e 100644 --- a/components/camera/transformpipeline/composed_test.go +++ b/components/camera/transformpipeline/composed_test.go @@ -9,13 +9,23 @@ import ( "go.viam.com/test" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" + "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/testutils/inject" "go.viam.com/rdk/utils" ) +type streamTest struct{} + +// Next will stream a color image. +func (*streamTest) Next(ctx context.Context) (image.Image, func(), error) { + return rimage.NewImage(1280, 720), func() {}, nil +} +func (*streamTest) Close(ctx context.Context) error { return nil } + func TestComposed(t *testing.T) { // create pointcloud source and fake robot robot := &inject.Robot{} @@ -25,6 +35,9 @@ func TestComposed(t *testing.T) { p := pointcloud.New() return p, p.Set(pointcloud.NewVector(0, 0, 0), pointcloud.NewColoredData(color.NRGBA{255, 1, 2, 255})) } + cloudSource.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + return &streamTest{}, nil + } cloudSource.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } @@ -53,14 +66,14 @@ func TestComposed(t *testing.T) { myOverlay, stream, err := newOverlayTransform(context.Background(), cloudSource, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - pic, _, err := myOverlay.GetImage(context.Background()) + pic, _, err := camera.ReadImage(context.Background(), myOverlay) test.That(t, err, test.ShouldBeNil) test.That(t, pic.Bounds(), test.ShouldResemble, image.Rect(0, 0, 1280, 720)) myPipeline, err := newTransformPipeline(context.Background(), cloudSource, conf, robot, logger) test.That(t, err, test.ShouldBeNil) defer myPipeline.Close(context.Background()) - pic, _, err = myPipeline.GetImage(context.Background()) + pic, _, err = camera.ReadImage(context.Background(), myPipeline) test.That(t, err, test.ShouldBeNil) test.That(t, pic.Bounds(), test.ShouldResemble, image.Rect(0, 0, 1280, 720)) diff --git a/components/camera/transformpipeline/depth_edges.go b/components/camera/transformpipeline/depth_edges.go index 82d02195910..841c2809cb3 100644 --- a/components/camera/transformpipeline/depth_edges.go +++ b/components/camera/transformpipeline/depth_edges.go @@ -56,7 +56,7 @@ func newDepthEdgesTransform(ctx context.Context, source camera.VideoSource, am u func (os *depthEdgesSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::depthEdges::Read") defer span.End() - i, closer, err := os.src.GetImage(ctx) + i, closer, err := camera.ReadImage(ctx, os.src) if err != nil { return nil, nil, err } diff --git a/components/camera/transformpipeline/depth_edges_test.go b/components/camera/transformpipeline/depth_edges_test.go index 9deded44067..e6ec7feebeb 100644 --- a/components/camera/transformpipeline/depth_edges_test.go +++ b/components/camera/transformpipeline/depth_edges_test.go @@ -33,7 +33,7 @@ func TestDepthSource(t *testing.T) { ds, stream, err := newDepthEdgesTransform(context.Background(), source, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - _, _, err = ds.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), ds) test.That(t, err, test.ShouldBeNil) test.That(t, ds.Close(context.Background()), test.ShouldBeNil) } @@ -66,7 +66,7 @@ func (h *depthSourceTestHelper) Process( ds, stream, err := newDepthEdgesTransform(context.Background(), source, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - edges, _, err := ds.GetImage(context.Background()) + edges, _, err := camera.ReadImage(context.Background(), ds) test.That(t, err, test.ShouldBeNil) test.That(t, ds.Close(context.Background()), test.ShouldBeNil) @@ -84,7 +84,7 @@ func (h *depthSourceTestHelper) Process( test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - output, _, err := rs.GetImage(context.Background()) + output, _, err := camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) preprocessed, err := rimage.ConvertImageToDepthMap(context.Background(), output) test.That(t, err, test.ShouldBeNil) @@ -105,7 +105,7 @@ func (h *depthSourceTestHelper) Process( ds, stream, err = newDepthEdgesTransform(context.Background(), source, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - processedEdges, _, err := ds.GetImage(context.Background()) + processedEdges, _, err := camera.ReadImage(context.Background(), ds) test.That(t, err, test.ShouldBeNil) test.That(t, ds.Close(context.Background()), test.ShouldBeNil) diff --git a/components/camera/transformpipeline/detector.go b/components/camera/transformpipeline/detector.go index 65134e4d2af..0728da400ea 100644 --- a/components/camera/transformpipeline/detector.go +++ b/components/camera/transformpipeline/detector.go @@ -84,7 +84,7 @@ func (ds *detectorSource) Read(ctx context.Context) (image.Image, func(), error) return nil, nil, fmt.Errorf("source_detector cant find vision service: %w", err) } // get image from source camera - img, release, err := ds.src.GetImage(ctx) + img, release, err := camera.ReadImage(ctx, ds.src) if err != nil { return nil, nil, fmt.Errorf("could not get next source image: %w", err) } diff --git a/components/camera/transformpipeline/detector_test.go b/components/camera/transformpipeline/detector_test.go index 919d44588ec..1b24e217aca 100644 --- a/components/camera/transformpipeline/detector_test.go +++ b/components/camera/transformpipeline/detector_test.go @@ -121,7 +121,7 @@ func TestColorDetectionSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) defer detector.Close(ctx) - resImg, _, err := detector.GetImage(ctx) + resImg, _, err := camera.ReadImage(ctx, detector) test.That(t, err, test.ShouldBeNil) ovImg := rimage.ConvertImage(resImg) test.That(t, ovImg.GetXY(852, 431), test.ShouldResemble, rimage.Red) @@ -146,7 +146,7 @@ func BenchmarkColorDetectionSource(b *testing.B) { b.ResetTimer() // begin benchmarking for i := 0; i < b.N; i++ { - _, _, _ = detector.GetImage(ctx) + _, _, _ = camera.ReadImage(ctx, detector) } test.That(b, detector.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/transformpipeline/mods.go b/components/camera/transformpipeline/mods.go index 20b542d38d6..0331f300399 100644 --- a/components/camera/transformpipeline/mods.go +++ b/components/camera/transformpipeline/mods.go @@ -63,7 +63,7 @@ func newRotateTransform(ctx context.Context, source camera.VideoSource, stream c func (rs *rotateSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::rotate::Read") defer span.End() - orig, release, err := rs.src.GetImage(ctx) + orig, release, err := camera.ReadImage(ctx, rs.src) if err != nil { return nil, nil, err } @@ -128,7 +128,7 @@ func newResizeTransform( func (rs *resizeSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::resize::Read") defer span.End() - orig, release, err := rs.src.GetImage(ctx) + orig, release, err := camera.ReadImage(ctx, rs.src) if err != nil { return nil, nil, err } @@ -200,7 +200,7 @@ func newCropTransform( func (cs *cropSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::crop::Read") defer span.End() - orig, release, err := cs.src.GetImage(ctx) + orig, release, err := camera.ReadImage(ctx, cs.src) if err != nil { return nil, nil, err } diff --git a/components/camera/transformpipeline/mods_test.go b/components/camera/transformpipeline/mods_test.go index 12cbd8722b4..e6bb1a5f1dc 100644 --- a/components/camera/transformpipeline/mods_test.go +++ b/components/camera/transformpipeline/mods_test.go @@ -32,7 +32,7 @@ func TestCrop(t *testing.T) { // test depth source source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: dm}, nil, camera.UnspecifiedStream) test.That(t, err, test.ShouldBeNil) - out, _, err := source.GetImage(context.Background()) + out, _, err := camera.ReadImage(context.Background(), source) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -40,7 +40,7 @@ func TestCrop(t *testing.T) { rs, stream, err := newCropTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - out, _, err = rs.GetImage(context.Background()) + out, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 10) @@ -51,7 +51,7 @@ func TestCrop(t *testing.T) { // test color source source, err = camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) test.That(t, err, test.ShouldBeNil) - out, _, err = source.GetImage(context.Background()) + out, _, err = camera.ReadImage(context.Background(), source) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -60,7 +60,7 @@ func TestCrop(t *testing.T) { rs, stream, err = newCropTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - out, _, err = rs.GetImage(context.Background()) + out, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 10) @@ -71,7 +71,7 @@ func TestCrop(t *testing.T) { rs, stream, err = newCropTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - out, _, err = rs.GetImage(context.Background()) + out, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 1) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 1) @@ -82,7 +82,7 @@ func TestCrop(t *testing.T) { rs, stream, err = newCropTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - _, _, err = rs.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "cropped image to 0 pixels") test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -111,7 +111,7 @@ func TestResizeColor(t *testing.T) { } source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{ColorImg: img}, nil, camera.UnspecifiedStream) test.That(t, err, test.ShouldBeNil) - out, _, err := source.GetImage(context.Background()) + out, _, err := camera.ReadImage(context.Background(), source) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -119,7 +119,7 @@ func TestResizeColor(t *testing.T) { rs, stream, err := newResizeTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - out, _, err = rs.GetImage(context.Background()) + out, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 30) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 20) @@ -138,7 +138,7 @@ func TestResizeDepth(t *testing.T) { } source, err := camera.NewVideoSourceFromReader(context.Background(), &fake.StaticSource{DepthImg: img}, nil, camera.UnspecifiedStream) test.That(t, err, test.ShouldBeNil) - out, _, err := source.GetImage(context.Background()) + out, _, err := camera.ReadImage(context.Background(), source) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 72) @@ -146,7 +146,7 @@ func TestResizeDepth(t *testing.T) { rs, stream, err := newResizeTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - out, _, err = rs.GetImage(context.Background()) + out, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, out.Bounds().Dx(), test.ShouldEqual, 60) test.That(t, out.Bounds().Dy(), test.ShouldEqual, 40) @@ -167,7 +167,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err := rs.GetImage(context.Background()) + rawImage, _, err := camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -184,7 +184,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImageDefault, _, err := rsDefault.GetImage(context.Background()) + rawImageDefault, _, err := camera.ReadImage(context.Background(), rsDefault) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -221,7 +221,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -253,7 +253,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -285,7 +285,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -317,7 +317,7 @@ func TestRotateColorSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -354,7 +354,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err := rs.GetImage(context.Background()) + rawImage, _, err := camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -372,7 +372,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImageDefault, _, err := rsDefault.GetImage(context.Background()) + rawImageDefault, _, err := camera.ReadImage(context.Background(), rsDefault) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -407,7 +407,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -439,7 +439,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -471,7 +471,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -503,7 +503,7 @@ func TestRotateDepthSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - rawImage, _, err = rs.GetImage(context.Background()) + rawImage, _, err = camera.ReadImage(context.Background(), rs) test.That(t, err, test.ShouldBeNil) test.That(t, rs.Close(context.Background()), test.ShouldBeNil) @@ -543,7 +543,8 @@ func BenchmarkColorRotate(b *testing.B) { b.ResetTimer() for n := 0; n < b.N; n++ { - rs.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), rs) + test.That(b, err, test.ShouldBeNil) } test.That(b, rs.Close(context.Background()), test.ShouldBeNil) test.That(b, source.Close(context.Background()), test.ShouldBeNil) @@ -567,7 +568,8 @@ func BenchmarkDepthRotate(b *testing.B) { b.ResetTimer() for n := 0; n < b.N; n++ { - rs.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), rs) + test.That(b, err, test.ShouldBeNil) } test.That(b, rs.Close(context.Background()), test.ShouldBeNil) test.That(b, source.Close(context.Background()), test.ShouldBeNil) diff --git a/components/camera/transformpipeline/pipeline.go b/components/camera/transformpipeline/pipeline.go index 0b86b0091a6..2932c61682d 100644 --- a/components/camera/transformpipeline/pipeline.go +++ b/components/camera/transformpipeline/pipeline.go @@ -100,7 +100,7 @@ func newTransformPipeline( return nil, errors.New("pipeline has no transforms in it") } // check if the source produces a depth image or color image - img, release, err := source.GetImage(ctx) + img, release, err := camera.ReadImage(ctx, source) var streamType camera.ImageType if err != nil { @@ -146,7 +146,7 @@ type transformPipeline struct { func (tp transformPipeline) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::Read") defer span.End() - return tp.src.GetImage(ctx) + return camera.ReadImage(ctx, tp.src) } func (tp transformPipeline) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { diff --git a/components/camera/transformpipeline/pipeline_test.go b/components/camera/transformpipeline/pipeline_test.go index d01e337b32b..eb31cd06e52 100644 --- a/components/camera/transformpipeline/pipeline_test.go +++ b/components/camera/transformpipeline/pipeline_test.go @@ -35,7 +35,7 @@ func TestTransformPipelineColor(t *testing.T) { source := gostream.NewVideoSource(&fake.StaticSource{ColorImg: img}, prop.Video{}) src, err := camera.WrapVideoSourceWithProjector(context.Background(), source, nil, camera.ColorStream) test.That(t, err, test.ShouldBeNil) - inImg, _, err := src.GetImage(context.Background()) + inImg, _, err := camera.ReadImage(context.Background(), src) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -43,7 +43,7 @@ func TestTransformPipelineColor(t *testing.T) { color, err := newTransformPipeline(context.Background(), src, transformConf, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := color.GetImage(context.Background()) + outImg, _, err := camera.ReadImage(context.Background(), color) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 20) @@ -81,7 +81,7 @@ func TestTransformPipelineDepth(t *testing.T) { source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: dm}, prop.Video{}) src, err := camera.WrapVideoSourceWithProjector(context.Background(), source, nil, camera.DepthStream) test.That(t, err, test.ShouldBeNil) - inImg, _, err := src.GetImage(context.Background()) + inImg, _, err := camera.ReadImage(context.Background(), src) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -89,7 +89,7 @@ func TestTransformPipelineDepth(t *testing.T) { depth, err := newTransformPipeline(context.Background(), src, transformConf, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := depth.GetImage(context.Background()) + outImg, _, err := camera.ReadImage(context.Background(), depth) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 40) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 30) @@ -136,7 +136,7 @@ func TestTransformPipelineDepth2(t *testing.T) { // first depth transform depth1, err := newTransformPipeline(context.Background(), source, transform1, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := depth1.GetImage(context.Background()) + outImg, _, err := camera.ReadImage(context.Background(), depth1) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 20) @@ -144,7 +144,7 @@ func TestTransformPipelineDepth2(t *testing.T) { // second depth image depth2, err := newTransformPipeline(context.Background(), source, transform2, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err = depth2.GetImage(context.Background()) + outImg, _, err = camera.ReadImage(context.Background(), depth2) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 40) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 30) @@ -174,7 +174,7 @@ func TestNullPipeline(t *testing.T) { } pipe, err := newTransformPipeline(context.Background(), source, transform2, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := pipe.GetImage(context.Background()) // should not transform anything + outImg, _, err := camera.ReadImage(context.Background(), pipe) // should not transform anything test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -208,7 +208,7 @@ func TestPipeIntoPipe(t *testing.T) { pipe1, err := newTransformPipeline(context.Background(), source, transform1, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err := pipe1.GetImage(context.Background()) + outImg, _, err := camera.ReadImage(context.Background(), pipe1) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -219,7 +219,7 @@ func TestPipeIntoPipe(t *testing.T) { // transform pipeline into pipeline pipe2, err := newTransformPipeline(context.Background(), pipe1, transform2, r, logger) test.That(t, err, test.ShouldBeNil) - outImg, _, err = pipe2.GetImage(context.Background()) + outImg, _, err = camera.ReadImage(context.Background(), pipe2) test.That(t, err, test.ShouldBeNil) test.That(t, outImg.Bounds().Dx(), test.ShouldEqual, 10) test.That(t, outImg.Bounds().Dy(), test.ShouldEqual, 20) diff --git a/components/camera/transformpipeline/preprocessing.go b/components/camera/transformpipeline/preprocessing.go index db113f4e74c..73624c1bcbe 100644 --- a/components/camera/transformpipeline/preprocessing.go +++ b/components/camera/transformpipeline/preprocessing.go @@ -42,7 +42,7 @@ func newDepthPreprocessTransform(ctx context.Context, source camera.VideoSource, func (os *preprocessDepthTransform) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::depthPreprocess::Read") defer span.End() - i, release, err := os.src.GetImage(ctx) + i, release, err := camera.ReadImage(ctx, os.src) if err != nil { return nil, nil, err } diff --git a/components/camera/transformpipeline/segmenter.go b/components/camera/transformpipeline/segmenter.go index 7b737863ab9..0ba705ce544 100644 --- a/components/camera/transformpipeline/segmenter.go +++ b/components/camera/transformpipeline/segmenter.go @@ -107,7 +107,7 @@ func (ss *segmenterSource) NextPointCloud(ctx context.Context) (pointcloud.Point // Read returns the image if the stream is valid, else error. func (ss *segmenterSource) Read(ctx context.Context) (image.Image, func(), error) { - img, release, err := ss.src.GetImage(ctx) + img, release, err := camera.ReadImage(ctx, ss.src) if err != nil { return nil, nil, fmt.Errorf("could not get next source image: %w", err) } diff --git a/components/camera/transformpipeline/segmenter_test.go b/components/camera/transformpipeline/segmenter_test.go index 4268d393982..a00242a3999 100644 --- a/components/camera/transformpipeline/segmenter_test.go +++ b/components/camera/transformpipeline/segmenter_test.go @@ -2,12 +2,14 @@ package transformpipeline import ( "context" + "image" "image/color" "testing" "go.viam.com/test" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" pc "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" @@ -24,6 +26,11 @@ func TestTransformSegmenterProps(t *testing.T) { vizServ := &inject.VisionService{} logger := logging.NewTestLogger(t) + cam.StreamFunc = func(ctx context.Context, + errHandlers ...gostream.ErrorHandler, + ) (gostream.MediaStream[image.Image], error) { + return &streamTest{}, nil + } cam.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } @@ -83,6 +90,11 @@ func TestTransformSegmenterFunctionality(t *testing.T) { vizServ := &inject.VisionService{} logger := logging.NewTestLogger(t) + cam.StreamFunc = func(ctx context.Context, + errHandlers ...gostream.ErrorHandler, + ) (gostream.MediaStream[image.Image], error) { + return &streamTest{}, nil + } cam.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } diff --git a/components/camera/transformpipeline/undistort.go b/components/camera/transformpipeline/undistort.go index fc4501ac3c1..a24dc18cceb 100644 --- a/components/camera/transformpipeline/undistort.go +++ b/components/camera/transformpipeline/undistort.go @@ -54,7 +54,7 @@ func newUndistortTransform( func (us *undistortSource) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::undistort::Read") defer span.End() - orig, release, err := us.originalSource.GetImage(ctx) + orig, release, err := camera.ReadImage(ctx, us.originalSource) if err != nil { return nil, nil, err } diff --git a/components/camera/transformpipeline/undistort_test.go b/components/camera/transformpipeline/undistort_test.go index 45809b5ff97..6227c3c4e78 100644 --- a/components/camera/transformpipeline/undistort_test.go +++ b/components/camera/transformpipeline/undistort_test.go @@ -52,7 +52,7 @@ func TestUndistortSetup(t *testing.T) { am = utils.AttributeMap{"intrinsic_parameters": undistortTestParams, "distortion_parameters": undistortTestBC} us, _, err := newUndistortTransform(context.Background(), source, camera.ImageType("fake"), am) test.That(t, err, test.ShouldBeNil) - _, _, err = us.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), us) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "do not know how to decode stream") test.That(t, us.Close(context.Background()), test.ShouldBeNil) @@ -61,7 +61,7 @@ func TestUndistortSetup(t *testing.T) { us, stream, err := newUndistortTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - _, _, err = us.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), us) test.That(t, err, test.ShouldBeNil) test.That(t, us.Close(context.Background()), test.ShouldBeNil) @@ -79,13 +79,13 @@ func TestUndistortImage(t *testing.T) { us, stream, err := newUndistortTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - corrected, _, err := us.GetImage(context.Background()) + corrected, _, err := camera.ReadImage(context.Background(), us) test.That(t, err, test.ShouldBeNil) result, ok := corrected.(*rimage.Image) test.That(t, ok, test.ShouldEqual, true) test.That(t, us.Close(context.Background()), test.ShouldBeNil) - sourceImg, _, err := source.GetImage(context.Background()) + sourceImg, _, err := camera.ReadImage(context.Background(), source) test.That(t, err, test.ShouldBeNil) expected, ok := sourceImg.(*rimage.Image) test.That(t, ok, test.ShouldEqual, true) @@ -103,7 +103,7 @@ func TestUndistortImage(t *testing.T) { us, stream, err = newUndistortTransform(context.Background(), source, camera.ColorStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.ColorStream) - _, _, err = us.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), us) test.That(t, err.Error(), test.ShouldContainSubstring, "img dimension and intrinsics don't match") test.That(t, us.Close(context.Background()), test.ShouldBeNil) } @@ -120,13 +120,13 @@ func TestUndistortDepthMap(t *testing.T) { us, stream, err := newUndistortTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - corrected, _, err := us.GetImage(context.Background()) + corrected, _, err := camera.ReadImage(context.Background(), us) test.That(t, err, test.ShouldBeNil) result, ok := corrected.(*rimage.DepthMap) test.That(t, ok, test.ShouldEqual, true) test.That(t, us.Close(context.Background()), test.ShouldBeNil) - sourceImg, _, err := source.GetImage(context.Background()) + sourceImg, _, err := camera.ReadImage(context.Background(), source) test.That(t, err, test.ShouldBeNil) expected, ok := sourceImg.(*rimage.DepthMap) test.That(t, ok, test.ShouldEqual, true) @@ -144,7 +144,7 @@ func TestUndistortDepthMap(t *testing.T) { us, stream, err = newUndistortTransform(context.Background(), source, camera.DepthStream, am) test.That(t, err, test.ShouldBeNil) test.That(t, stream, test.ShouldEqual, camera.DepthStream) - _, _, err = us.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), us) test.That(t, err.Error(), test.ShouldContainSubstring, "img dimension and intrinsics don't match") test.That(t, us.Close(context.Background()), test.ShouldBeNil) @@ -159,7 +159,7 @@ func TestUndistortDepthMap(t *testing.T) { us, stream, err = newUndistortTransform(context.Background(), source, camera.DepthStream, am) test.That(t, stream, test.ShouldEqual, camera.DepthStream) test.That(t, err, test.ShouldBeNil) - _, _, err = us.GetImage(context.Background()) + _, _, err = camera.ReadImage(context.Background(), us) test.That(t, err.Error(), test.ShouldContainSubstring, "don't know how to make DepthMap") test.That(t, us.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/videosource/webcam.go b/components/camera/videosource/webcam.go index e578cf42d57..5703063fffb 100644 --- a/components/camera/videosource/webcam.go +++ b/components/camera/videosource/webcam.go @@ -28,6 +28,7 @@ import ( "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" ) @@ -565,8 +566,17 @@ func (c *monitoredWebcam) Stream(ctx context.Context, errHandlers ...gostream.Er return c.exposedSwapper.Stream(ctx, errHandlers...) } -func (c *monitoredWebcam) GetImage(ctx context.Context) (image.Image, func(), error) { - return camera.ReadImage(ctx, c.underlyingSource) +func (c *monitoredWebcam) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + img, release, err := camera.ReadImage(ctx, c.underlyingSource) + if err != nil { + return nil, "", err + } + defer release() + imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) + if err != nil { + return nil, "", err + } + return imgBytes, mimeType, nil } func (c *monitoredWebcam) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { diff --git a/components/camera/videosourcewrappers.go b/components/camera/videosourcewrappers.go index f8af8ca2fb7..a9ee5eb6d4a 100644 --- a/components/camera/videosourcewrappers.go +++ b/components/camera/videosourcewrappers.go @@ -2,7 +2,6 @@ package camera import ( "context" - "image" "time" "github.com/pion/mediadevices/pkg/prop" @@ -198,8 +197,17 @@ func (vs *videoSource) Stream(ctx context.Context, errHandlers ...gostream.Error return vs.videoSource.Stream(ctx, errHandlers...) } -func (vs *videoSource) GetImage(ctx context.Context) (image.Image, func(), error) { - return ReadImage(ctx, vs.videoSource) +func (vs *videoSource) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + img, release, err := ReadImage(ctx, vs.videoSource) + if err != nil { + return nil, "", err + } + defer release() + outBytes, err := rimage.EncodeImage(ctx, img, mimeType) + if err != nil { + return nil, "", err + } + return outBytes, mimeType, nil } // Images is for getting simultaneous images from different sensors diff --git a/robot/client/client.go b/robot/client/client.go index 6d314c4126b..c54c077ad8a 100644 --- a/robot/client/client.go +++ b/robot/client/client.go @@ -943,7 +943,6 @@ func (rc *RobotClient) Status(ctx context.Context, resourceNames []resource.Name names = append(names, rprotoutils.ResourceNameToProto(name)) } - //nolint:staticcheck // the status API is deprecated resp, err := rc.client.GetStatus(ctx, &pb.GetStatusRequest{ResourceNames: names}) if err != nil { return nil, err diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 3064619e0d4..a0b73ffa85b 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -55,7 +55,6 @@ import ( "go.viam.com/rdk/components/sensor" "go.viam.com/rdk/components/servo" "go.viam.com/rdk/config" - "go.viam.com/rdk/gostream" rgrpc "go.viam.com/rdk/grpc" "go.viam.com/rdk/logging" "go.viam.com/rdk/operation" @@ -332,13 +331,12 @@ func TestStatusClient(t *testing.T) { var imgBuf bytes.Buffer test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil) - var imageReleased bool - var imageReleasedMu sync.Mutex - injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return img, func() {}, nil + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + img, err := rimage.EncodeImage(ctx, img, mimeType) + if err != nil { + return nil, "", err + } + return img, mimeType, nil } injectInputDev := &inject.InputController{} @@ -510,7 +508,7 @@ func TestStatusClient(t *testing.T) { camera1, err := camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - _, _, err = camera1.GetImage(context.Background()) + _, _, err = camera1.Image(context.Background(), "", camera.Extra{}) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "not found") @@ -588,15 +586,13 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA) - frame, _, err := camera1.GetImage(ctx) + frameBytes, mimeType, err := camera1.Image(context.Background(), rutils.MimeTypeRawRGBA, camera.Extra{}) + test.That(t, err, test.ShouldBeNil) + frame, err := rimage.DecodeImage(context.Background(), frameBytes, mimeType) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() gripper1, err = gripper.FromRobot(client, "gripper1") test.That(t, err, test.ShouldBeNil) @@ -975,7 +971,7 @@ func TestClientStreamDisconnectHandler(t *testing.T) { t.Helper() client.connected.Store(false) - //nolint:staticcheck // the status API is deprecated + _, err = client.client.StreamStatus(context.Background(), &pb.StreamStatusRequest{}) test.That(t, status.Code(err), test.ShouldEqual, codes.Unavailable) test.That(t, err.Error(), test.ShouldContainSubstring, fmt.Sprintf("not connected to remote robot at %s", listener.Addr().String())) @@ -986,7 +982,6 @@ func TestClientStreamDisconnectHandler(t *testing.T) { t.Run("stream call to connected remote", func(t *testing.T) { t.Helper() - //nolint:staticcheck // the status API is deprecated ssc, err := client.client.StreamStatus(context.Background(), &pb.StreamStatusRequest{}) test.That(t, err, test.ShouldBeNil) ssc.Recv() @@ -996,7 +991,6 @@ func TestClientStreamDisconnectHandler(t *testing.T) { t.Run("receive call from stream of disconnected remote", func(t *testing.T) { t.Helper() - //nolint:staticcheck // the status API is deprecated ssc, err := client.client.StreamStatus(context.Background(), &pb.StreamStatusRequest{}) test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 4a17f6e8b86..1e25f949f8d 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -58,6 +58,7 @@ import ( "go.viam.com/rdk/protoutils" "go.viam.com/rdk/referenceframe" "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" "go.viam.com/rdk/robot" "go.viam.com/rdk/robot/client" "go.viam.com/rdk/robot/framesystem" @@ -93,7 +94,9 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - pic, _, err := c1.GetImage(context.Background()) + outBytes, mimeType, err := c1.Image(context.Background(), "", camera.Extra{}) + test.That(t, err, test.ShouldBeNil) + pic, err := rimage.DecodeImage(context.Background(), outBytes, mimeType) test.That(t, err, test.ShouldBeNil) bounds := pic.Bounds() diff --git a/robot/server/server_test.go b/robot/server/server_test.go index 3270ac69edd..4dbe7141174 100644 --- a/robot/server/server_test.go +++ b/robot/server/server_test.go @@ -612,7 +612,7 @@ func TestServerGetStatus(t *testing.T) { injectRobot.StatusFunc = func(ctx context.Context, resourceNames []resource.Name) ([]robot.Status, error) { return nil, passedErr } - //nolint:staticcheck // the status API is deprecated + _, err := server.GetStatus(context.Background(), &pb.GetStatusRequest{}) test.That(t, err, test.ShouldBeError, passedErr) }) @@ -629,7 +629,6 @@ func TestServerGetStatus(t *testing.T) { ResourceNames: []*commonpb.ResourceName{}, } - //nolint:staticcheck // the status API is deprecated _, err := server.GetStatus(context.Background(), req) test.That( t, @@ -665,7 +664,6 @@ func TestServerGetStatus(t *testing.T) { ResourceNames: []*commonpb.ResourceName{protoutils.ResourceNameToProto(aStatus.Name)}, } - //nolint:staticcheck // the status API is deprecated resp, err := server.GetStatus(context.Background(), req) test.That(t, err, test.ShouldBeNil) test.That(t, len(resp.Status), test.ShouldEqual, 1) @@ -714,7 +712,6 @@ func TestServerGetStatus(t *testing.T) { }, } - //nolint:staticcheck // the status API is deprecated resp, err := server.GetStatus(context.Background(), req) test.That(t, err, test.ShouldBeNil) test.That(t, len(resp.Status), test.ShouldEqual, 2) @@ -748,7 +745,7 @@ func TestServerGetStatus(t *testing.T) { ctx: cancelCtx, messageCh: messageCh, } - //nolint:staticcheck // the status API is deprecated + err := server.StreamStatus(&pb.StreamStatusRequest{Every: durationpb.New(time.Second)}, streamServer) test.That(t, err, test.ShouldEqual, err1) }) @@ -769,7 +766,7 @@ func TestServerGetStatus(t *testing.T) { fail: true, } dur := 100 * time.Millisecond - //nolint:staticcheck // the status API is deprecated + err := server.StreamStatus(&pb.StreamStatusRequest{Every: durationpb.New(dur)}, streamServer) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "send fail") @@ -790,7 +787,6 @@ func TestServerGetStatus(t *testing.T) { } dur := 100 * time.Millisecond - //nolint:staticcheck // the status API is deprecated streamErr := server.StreamStatus(&pb.StreamStatusRequest{Every: durationpb.New(dur)}, streamServer) test.That(t, streamErr, test.ShouldResemble, context.DeadlineExceeded) }) @@ -821,7 +817,6 @@ func TestServerGetStatus(t *testing.T) { start := time.Now() done := make(chan struct{}) go func() { - //nolint:staticcheck // the status API is deprecated streamErr = server.StreamStatus(&pb.StreamStatusRequest{Every: durationpb.New(dur)}, streamServer) close(done) }() diff --git a/robot/web/web_test.go b/robot/web/web_test.go index be12932ddc1..c4199a5b22a 100644 --- a/robot/web/web_test.go +++ b/robot/web/web_test.go @@ -1151,12 +1151,11 @@ func TestRawClientOperation(t *testing.T) { client := robotpb.NewRobotServiceClient(conn) var hdr metadata.MD - //nolint:staticcheck // the status API is deprecated + _, err = client.GetStatus(ctx, &robotpb.GetStatusRequest{}, grpc.Header(&hdr)) test.That(t, err, test.ShouldBeNil) checkOpID(hdr, true) - //nolint:staticcheck // the status API is deprecated streamClient, err := client.StreamStatus(ctx, &robotpb.StreamStatusRequest{}) test.That(t, err, test.ShouldBeNil) md, err := streamClient.Header() @@ -1218,7 +1217,7 @@ func TestInboundMethodTimeout(t *testing.T) { client := robotpb.NewRobotServiceClient(conn) // Use GetStatus to call injected status function. - //nolint:staticcheck // the status API is deprecated + _, err = client.GetStatus(ctx, &robotpb.GetStatusRequest{}) test.That(t, err, test.ShouldBeNil) @@ -1254,7 +1253,7 @@ func TestInboundMethodTimeout(t *testing.T) { // Use GetStatus and a context with a deadline to call injected status function. overrideCtx, cancel := context.WithTimeout(context.Background(), 5*time.Minute) defer cancel() - //nolint:staticcheck // the status API is deprecated + _, err = client.GetStatus(overrideCtx, &robotpb.GetStatusRequest{}) test.That(t, err, test.ShouldBeNil) @@ -1290,7 +1289,7 @@ func TestInboundMethodTimeout(t *testing.T) { client := robotpb.NewRobotServiceClient(conn) // Use GetStatus to call injected status function. - //nolint:staticcheck // the status API is deprecated + _, err = client.GetStatus(ctx, &robotpb.GetStatusRequest{}) test.That(t, err, test.ShouldBeNil) @@ -1325,7 +1324,7 @@ func TestInboundMethodTimeout(t *testing.T) { // Use GetStatus and a context with a deadline to call injected status function. overrideCtx, cancel := context.WithTimeout(context.Background(), 5*time.Minute) defer cancel() - //nolint:staticcheck // the status API is deprecated + _, err = client.GetStatus(overrideCtx, &robotpb.GetStatusRequest{}) test.That(t, err, test.ShouldBeNil) diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index ad3464dac29..104213107c0 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -26,6 +26,7 @@ import ( "go.viam.com/rdk/data" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" datasync "go.viam.com/rdk/services/datamanager/builtin/sync" "go.viam.com/rdk/spatialmath" "go.viam.com/rdk/testutils/inject" @@ -153,10 +154,16 @@ func TestSyncEnabled(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - GetImageFunc: func( + ImageFunc: func( ctx context.Context, - ) (image.Image, func(), error) { - return imgPng, func() {}, nil + mimeType string, + extra map[string]interface{}, + ) ([]byte, string, error) { + outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + if err != nil { + return nil, "", err + } + return outBytes, "", nil }, }, }) @@ -352,12 +359,18 @@ func TestDataCaptureUploadIntegration(t *testing.T) { if tc.dataType == v1.DataType_DATA_TYPE_TABULAR_SENSOR { config, deps = setupConfig(t, r, enabledTabularCollectorConfigPath) } else { - r = setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ + r := setupRobot(nil, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - GetImageFunc: func( + ImageFunc: func( ctx context.Context, - ) (image.Image, func(), error) { - return imgPng, func() {}, nil + mimeType string, + extra map[string]interface{}, + ) ([]byte, string, error) { + outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + if err != nil { + return nil, "", err + } + return outBytes, "", nil }, }, }) @@ -755,10 +768,16 @@ func TestStreamingDCUpload(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(nil, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - GetImageFunc: func( + ImageFunc: func( ctx context.Context, - ) (image.Image, func(), error) { - return imgPng, func() {}, nil + mimeType string, + extra map[string]interface{}, + ) ([]byte, string, error) { + outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + if err != nil { + return nil, "", err + } + return outBytes, "", nil }, }, }) @@ -994,10 +1013,16 @@ func TestSyncConfigUpdateBehavior(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(nil, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - GetImageFunc: func( + ImageFunc: func( ctx context.Context, - ) (image.Image, func(), error) { - return imgPng, func() {}, nil + mimeType string, + extra map[string]interface{}, + ) ([]byte, string, error) { + outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + if err != nil { + return nil, "", err + } + return outBytes, "", nil }, }, }) diff --git a/services/datamanager/builtin/builtin_test.go b/services/datamanager/builtin/builtin_test.go index 0866fa33dea..e991d1ca7c3 100644 --- a/services/datamanager/builtin/builtin_test.go +++ b/services/datamanager/builtin/builtin_test.go @@ -3,7 +3,6 @@ package builtin import ( "cmp" "context" - "image" "io/fs" "maps" "math" @@ -34,6 +33,7 @@ import ( "go.viam.com/rdk/logging" "go.viam.com/rdk/referenceframe" "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" "go.viam.com/rdk/services/datamanager" "go.viam.com/rdk/services/datamanager/builtin/capture" datasync "go.viam.com/rdk/services/datamanager/builtin/sync" @@ -449,10 +449,16 @@ func TestSync(t *testing.T) { if tc.dataType == v1.DataType_DATA_TYPE_BINARY_SENSOR { r = setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ - GetImageFunc: func( + ImageFunc: func( ctx context.Context, - ) (image.Image, func(), error) { - return imgPng, func() {}, nil + mimeType string, + extra map[string]interface{}, + ) ([]byte, string, error) { + outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + if err != nil { + return nil, "", err + } + return outBytes, "", nil }, }, }) diff --git a/services/sensors/server_test.go b/services/sensors/server_test.go index 55744f23577..f79231605d4 100644 --- a/services/sensors/server_test.go +++ b/services/sensors/server_test.go @@ -32,7 +32,7 @@ func TestServerGetSensors(t *testing.T) { sMap := map[resource.Name]sensors.Service{} server, err := newServer(sMap) test.That(t, err, test.ShouldBeNil) - //nolint:staticcheck + _, err = server.GetSensors(context.Background(), &pb.GetSensorsRequest{}) test.That(t, err, test.ShouldBeError, errors.New("resource \"rdk:service:sensors/\" not found")) }) @@ -49,7 +49,6 @@ func TestServerGetSensors(t *testing.T) { return nil, passedErr } - //nolint:staticcheck _, err = server.GetSensors(context.Background(), &pb.GetSensorsRequest{Name: testSvcName1.ShortName()}) test.That(t, err, test.ShouldBeError, passedErr) }) @@ -72,15 +71,12 @@ func TestServerGetSensors(t *testing.T) { ext, err := protoutils.StructToStructPb(extra) test.That(t, err, test.ShouldBeNil) - //nolint:staticcheck resp, err := server.GetSensors(context.Background(), &pb.GetSensorsRequest{Name: testSvcName1.ShortName(), Extra: ext}) test.That(t, err, test.ShouldBeNil) test.That(t, extraOptions, test.ShouldResemble, extra) - //nolint:staticcheck convertedNames := make([]resource.Name, 0, len(resp.SensorNames)) - //nolint:staticcheck for _, rn := range resp.SensorNames { convertedNames = append(convertedNames, rprotoutils.ResourceNameFromProto(rn)) } @@ -94,7 +90,6 @@ func TestServerGetReadings(t *testing.T) { server, err := newServer(sMap) test.That(t, err, test.ShouldBeNil) - //nolint:staticcheck _, err = server.GetReadings(context.Background(), &pb.GetReadingsRequest{}) test.That(t, err, test.ShouldBeError, errors.New("resource \"rdk:service:sensors/\" not found")) }) @@ -113,13 +108,11 @@ func TestServerGetReadings(t *testing.T) { return nil, passedErr } - //nolint:staticcheck req := &pb.GetReadingsRequest{ Name: testSvcName1.ShortName(), SensorNames: []*commonpb.ResourceName{}, } - //nolint:staticcheck _, err = server.GetReadings(context.Background(), req) test.That(t, err, test.ShouldBeError, passedErr) }) @@ -149,18 +142,15 @@ func TestServerGetReadings(t *testing.T) { ext, err := protoutils.StructToStructPb(extra) test.That(t, err, test.ShouldBeNil) - //nolint:staticcheck req := &pb.GetReadingsRequest{ Name: testSvcName1.ShortName(), SensorNames: []*commonpb.ResourceName{}, Extra: ext, } - //nolint:staticcheck resp, err := server.GetReadings(context.Background(), req) test.That(t, err, test.ShouldBeNil) - //nolint:staticcheck test.That(t, len(resp.Readings), test.ShouldEqual, 2) test.That(t, extraOptions, test.ShouldResemble, extra) @@ -173,10 +163,8 @@ func TestServerGetReadings(t *testing.T) { } observed := map[resource.Name]interface{}{ - //nolint:staticcheck rprotoutils.ResourceNameFromProto(resp.Readings[0].Name): conv(resp.Readings[0].Readings), - //nolint:staticcheck rprotoutils.ResourceNameFromProto(resp.Readings[1].Name): conv(resp.Readings[1].Readings), } test.That(t, observed, test.ShouldResemble, expected) @@ -199,7 +187,6 @@ func TestServerDoCommand(t *testing.T) { Command: cmd, } - //nolint:staticcheck doCommandResponse, err := server.DoCommand(context.Background(), doCommandRequest) test.That(t, err, test.ShouldBeNil) diff --git a/services/vision/obstaclesdepth/obstacles_depth.go b/services/vision/obstaclesdepth/obstacles_depth.go index 6c68108e5d3..7768f260c78 100644 --- a/services/vision/obstaclesdepth/obstacles_depth.go +++ b/services/vision/obstaclesdepth/obstacles_depth.go @@ -13,6 +13,7 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -117,12 +118,19 @@ func (o *obsDepth) buildObsDepth(logger logging.Logger) func( // buildObsDepthNoIntrinsics will return the median depth in the depth map as a Geometry point. func (o *obsDepth) obsDepthNoIntrinsics(ctx context.Context, src camera.VideoSource) ([]*vision.Object, error) { - pic, release, err := src.GetImage(ctx) + ext, ok := camera.FromContext(ctx) + if !ok { + ext = camera.Extra{} + } + imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), ext) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } - defer release() + pic, err := rimage.DecodeImage(ctx, imgBytes, mimeType) + if err != nil { + return nil, errors.Errorf("could not decode image from %s", src) + } dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { return nil, errors.New("could not convert image to depth map") @@ -149,11 +157,18 @@ func (o *obsDepth) obsDepthWithIntrinsics(ctx context.Context, src camera.VideoS if o.intrinsics == nil { return nil, errors.New("tried to build obstacles depth with intrinsics but no instrinsics found") } - pic, release, err := src.GetImage(ctx) + ext, ok := camera.FromContext(ctx) + if !ok { + ext = camera.Extra{} + } + imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), ext) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } - defer release() + pic, err := rimage.DecodeImage(ctx, imgBytes, mimeType) + if err != nil { + return nil, errors.Errorf("could not decode image from %s", src) + } dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { return nil, errors.New("could not convert image to depth map") diff --git a/services/vision/vision.go b/services/vision/vision.go index bde6e35ed67..e7c867dc689 100644 --- a/services/vision/vision.go +++ b/services/vision/vision.go @@ -15,8 +15,11 @@ import ( "go.viam.com/rdk/components/camera" "go.viam.com/rdk/data" + "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" "go.viam.com/rdk/robot" + "go.viam.com/rdk/utils" viz "go.viam.com/rdk/vision" "go.viam.com/rdk/vision/classification" "go.viam.com/rdk/vision/objectdetection" @@ -271,11 +274,14 @@ func (vm *vizModel) DetectionsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, release, err := cam.GetImage(ctx) + imgBytes, mimeType, err := cam.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra) if err != nil { return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } - defer release() + img, err := rimage.DecodeImage(ctx, imgBytes, mimeType) + if err != nil { + return nil, errors.Errorf("could not decode image from %s", cameraName) + } return vm.detectorFunc(ctx, img) } @@ -314,11 +320,14 @@ func (vm *vizModel) ClassificationsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, release, err := cam.GetImage(ctx) + imgBytes, mimeType, err := cam.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra) if err != nil { return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } - defer release() + img, err := rimage.DecodeImage(ctx, imgBytes, mimeType) + if err != nil { + return nil, errors.Errorf("could not decode image from %s", cameraName) + } fullClassifications, err := vm.classifierFunc(ctx, img) if err != nil { return nil, errors.Wrap(err, "could not get classifications from image") @@ -364,11 +373,14 @@ func (vm *vizModel) CaptureAllFromCamera( if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, release, err := cam.GetImage(ctx) + imgBytes, mimeType, err := cam.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra) if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not get image from %s", cameraName) } - defer release() + img, err := rimage.DecodeImage(ctx, imgBytes, mimeType) + if err != nil { + return viscapture.VisCapture{}, errors.Errorf("could not decode image from %s", cameraName) + } logger := vm.r.Logger() var detections []objectdetection.Detection if opt.ReturnDetections { diff --git a/testutils/inject/camera.go b/testutils/inject/camera.go index c975e18d0c0..9d87129cf6f 100644 --- a/testutils/inject/camera.go +++ b/testutils/inject/camera.go @@ -2,12 +2,12 @@ package inject import ( "context" - "image" "github.com/pkg/errors" "go.viam.com/rdk/components/camera" "go.viam.com/rdk/components/camera/rtppassthrough" + "go.viam.com/rdk/gostream" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage/transform" @@ -19,12 +19,16 @@ type Camera struct { name resource.Name RTPPassthroughSource rtppassthrough.Source DoFunc func(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error) - ImagesFunc func(ctx context.Context) ([]camera.NamedImage, resource.ResponseMetadata, error) - GetImageFunc func(ctx context.Context) (image.Image, func(), error) - NextPointCloudFunc func(ctx context.Context) (pointcloud.PointCloud, error) - ProjectorFunc func(ctx context.Context) (transform.Projector, error) - PropertiesFunc func(ctx context.Context) (camera.Properties, error) - CloseFunc func(ctx context.Context) error + StreamFunc func( + ctx context.Context, + errHandlers ...gostream.ErrorHandler, + ) (gostream.VideoStream, error) + ImagesFunc func(ctx context.Context) ([]camera.NamedImage, resource.ResponseMetadata, error) + ImageFunc func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) + NextPointCloudFunc func(ctx context.Context) (pointcloud.PointCloud, error) + ProjectorFunc func(ctx context.Context) (transform.Projector, error) + PropertiesFunc func(ctx context.Context) (camera.Properties, error) + CloseFunc func(ctx context.Context) error } // NewCamera returns a new injected camera. @@ -48,15 +52,29 @@ func (c *Camera) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, err return nil, errors.New("NextPointCloud unimplemented") } -// GetImage calls the injected GetImage or the real version. -func (c *Camera) GetImage(ctx context.Context) (image.Image, func(), error) { - if c.GetImageFunc != nil { - return c.GetImageFunc(ctx) +// Stream calls the injected Stream or the real version. +func (c *Camera) Stream( + ctx context.Context, + errHandlers ...gostream.ErrorHandler, +) (gostream.VideoStream, error) { + if c.StreamFunc != nil { + return c.StreamFunc(ctx, errHandlers...) + } + if c.Camera != nil { + return c.Camera.Stream(ctx, errHandlers...) + } + return nil, errors.Wrap(ctx.Err(), "no stream function available") +} + +// Image calls the injected Image or the real version. +func (c *Camera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + if c.ImageFunc != nil { + return c.ImageFunc(ctx, mimeType, extra) } if c.Camera != nil { - return c.Camera.GetImage(ctx) + return c.Camera.Image(ctx, mimeType, extra) } - return nil, func() {}, errors.Wrap(ctx.Err(), "no GetImage function available") + return nil, "", errors.Wrap(ctx.Err(), "no GetImage function available") } // Properties calls the injected Properties or the real version. From 59c36ec622743528a2e5e720f06b68dbe0c24f19 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 6 Nov 2024 14:05:38 -0500 Subject: [PATCH 04/51] Fix tests --- components/camera/client.go | 6 ++--- robot/client/client_test.go | 24 +++++++------------ robot/impl/local_robot_test.go | 2 +- .../datamanager/builtin/builtin_sync_test.go | 2 +- .../vision/obstaclesdepth/obstacles_depth.go | 4 ++-- 5 files changed, 15 insertions(+), 23 deletions(-) diff --git a/components/camera/client.go b/components/camera/client.go index b5081575f5a..a720b2c402e 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -179,7 +179,7 @@ func (c *client) Stream( } func (c *client) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { - ctx, span := trace.StartSpan(ctx, "camera::client::GetImage") + ctx, span := trace.StartSpan(ctx, "camera::client::Image") defer span.End() expectedType, _ := utils.CheckLazyMIMEType(mimeType) @@ -202,8 +202,8 @@ func (c *client) Image(ctx context.Context, mimeType string, extra map[string]in resp.MimeType = mimeType } - mimeType = utils.WithLazyMIMEType(resp.MimeType) - return resp.Image, mimeType, nil + resp.MimeType = utils.WithLazyMIMEType(resp.MimeType) + return resp.Image, resp.MimeType, nil } func (c *client) Images(ctx context.Context) ([]NamedImage, resource.ResponseMetadata, error) { diff --git a/robot/client/client_test.go b/robot/client/client_test.go index b452af0049f..a244849af96 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -55,7 +55,6 @@ import ( "go.viam.com/rdk/components/sensor" "go.viam.com/rdk/components/servo" "go.viam.com/rdk/config" - "go.viam.com/rdk/gostream" rgrpc "go.viam.com/rdk/grpc" "go.viam.com/rdk/logging" "go.viam.com/rdk/operation" @@ -332,15 +331,10 @@ func TestStatusClient(t *testing.T) { var imgBuf bytes.Buffer test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil) - var imageReleased bool - var imageReleasedMu sync.Mutex - injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - imageReleasedMu.Lock() - imageReleased = true - imageReleasedMu.Unlock() - return img, func() {}, nil - })), nil + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + resBytes, err := rimage.EncodeImage(ctx, img, mimeType) + test.That(t, err, test.ShouldBeNil) + return resBytes, mimeType, nil } injectInputDev := &inject.InputController{} @@ -512,7 +506,7 @@ func TestStatusClient(t *testing.T) { camera1, err := camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - _, _, err = camera.ReadImage(context.Background(), camera1) + _, _, err = camera1.Image(context.Background(), rutils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "not found") @@ -590,15 +584,13 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA) - frame, _, err := camera.ReadImage(ctx, camera1) + frameBytes, mimeType, err := camera1.Image(context.Background(), rutils.MimeTypeRawRGBA, nil) + test.That(t, err, test.ShouldBeNil) + frame, err := rimage.DecodeImage(context.Background(), frameBytes, mimeType) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion - imageReleasedMu.Lock() - test.That(t, imageReleased, test.ShouldBeTrue) - imageReleasedMu.Unlock() gripper1, err = gripper.FromRobot(client, "gripper1") test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 1e25f949f8d..650f1b0f1c9 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -94,7 +94,7 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - outBytes, mimeType, err := c1.Image(context.Background(), "", camera.Extra{}) + outBytes, mimeType, err := c1.Image(context.Background(), rutils.MimeTypeJPEG, camera.Extra{}) test.That(t, err, test.ShouldBeNil) pic, err := rimage.DecodeImage(context.Background(), outBytes, mimeType) test.That(t, err, test.ShouldBeNil) diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index 104213107c0..ed33fdfaa4d 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -163,7 +163,7 @@ func TestSyncEnabled(t *testing.T) { if err != nil { return nil, "", err } - return outBytes, "", nil + return outBytes, mimeType, nil }, }, }) diff --git a/services/vision/obstaclesdepth/obstacles_depth.go b/services/vision/obstaclesdepth/obstacles_depth.go index 7768f260c78..29d5ebd3ae6 100644 --- a/services/vision/obstaclesdepth/obstacles_depth.go +++ b/services/vision/obstaclesdepth/obstacles_depth.go @@ -122,7 +122,7 @@ func (o *obsDepth) obsDepthNoIntrinsics(ctx context.Context, src camera.VideoSou if !ok { ext = camera.Extra{} } - imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), ext) + imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), ext) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } @@ -161,7 +161,7 @@ func (o *obsDepth) obsDepthWithIntrinsics(ctx context.Context, src camera.VideoS if !ok { ext = camera.Extra{} } - imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), ext) + imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), ext) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } From 16079facd0d8c0e797d172385e2c811ff4580020 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 6 Nov 2024 15:56:57 -0500 Subject: [PATCH 05/51] Delete ReadImager and fix mimetype formatting in data collector --- components/camera/collector.go | 11 ++-- components/camera/server.go | 54 ++----------------- .../datamanager/builtin/builtin_sync_test.go | 2 +- 3 files changed, 11 insertions(+), 56 deletions(-) diff --git a/components/camera/collector.go b/components/camera/collector.go index d52fbdae2b4..c6e036ab7a0 100644 --- a/components/camera/collector.go +++ b/components/camera/collector.go @@ -95,7 +95,11 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d ctx = context.WithValue(ctx, data.FromDMContextKey{}, true) - img, _, err := camera.Image(ctx, mimeType.String(), Extra{}) + mimeStr := new(wrapperspb.StringValue) + if err := mimeType.UnmarshalTo(mimeStr); err != nil { + return nil, err + } + img, _, err := camera.Image(ctx, mimeStr.Value, Extra{}) if err != nil { // A modular filter component can be created to filter the readings from a component. The error ErrNoCaptureToStore // is used in the datamanager to exclude readings from being captured and stored. @@ -106,11 +110,6 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d return nil, data.FailedToReadErr(params.ComponentName, readImage.String(), err) } - mimeStr := new(wrapperspb.StringValue) - if err := mimeType.UnmarshalTo(mimeStr); err != nil { - return nil, err - } - return img, nil }) return data.NewCollector(cFunc, params) diff --git a/components/camera/server.go b/components/camera/server.go index 6d6fc3a8bdb..603ed40d63e 100644 --- a/components/camera/server.go +++ b/components/camera/server.go @@ -35,12 +35,6 @@ func NewRPCServiceServer(coll resource.APIResourceCollection[Camera]) interface{ return &serviceServer{coll: coll, logger: logger, imgTypes: imgTypes} } -// ReadImager is an interface that cameras can implement when they allow for returning a single -// image object. -type ReadImager interface { - Read(ctx context.Context) (image.Image, func(), error) -} - // GetImage returns an image from a camera of the underlying robot. If a specific MIME type // is requested and is not available, an error is returned. func (s *serviceServer) GetImage( @@ -74,52 +68,14 @@ func (s *serviceServer) GetImage( req.MimeType = utils.MimeTypeJPEG } } - req.MimeType = utils.WithLazyMIMEType(req.MimeType) - ext := req.Extra.AsMap() - ctx = NewContext(ctx, ext) - - resp := pb.GetImageResponse{} - switch castedCam := cam.(type) { - case ReadImager: - // RSDK-8663: If available, call a method that reads exactly one image. The default - // `ReadImage` implementation will otherwise create a gostream `Stream`, call `Next` and - // `Close` the stream. However, between `Next` and `Close`, the stream may have pulled a - // second image from the underlying camera. This is particularly noticeable on camera - // clients. Where a second `GetImage` request can be processed/returned over the - // network. Just to be discarded. - // RSDK-9132(sean yu): In addition to what Dan said above, ReadImager is important - // for camera components that rely on the `release` functionality provided by gostream's `Read` - // such as viamrtsp. - // (check that this comment is 100% true before code review then delete this paranthetical statement) - img, release, err := castedCam.Read(ctx) - if err != nil { - return nil, err - } - defer func() { - if release != nil { - release() - } - }() - - actualMIME, _ := utils.CheckLazyMIMEType(req.MimeType) - resp.MimeType = actualMIME - outBytes, err := rimage.EncodeImage(ctx, img, req.MimeType) - if err != nil { - return nil, err - } - resp.Image = outBytes - default: - imgBytes, mimeType, err := cam.Image(ctx, req.MimeType, ext) - if err != nil { - return nil, err - } - actualMIME, _ := utils.CheckLazyMIMEType(mimeType) - resp.MimeType = actualMIME - resp.Image = imgBytes + imgBytes, mimeType, err := cam.Image(ctx, req.MimeType, req.Extra.AsMap()) + if err != nil { + return nil, err } - return &resp, nil + actualMIME, _ := utils.CheckLazyMIMEType(mimeType) + return &pb.GetImageResponse{MimeType: actualMIME, Image: imgBytes}, nil } // GetImages returns a list of images and metadata from a camera of the underlying robot. diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index ed33fdfaa4d..09270c93f0a 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -359,7 +359,7 @@ func TestDataCaptureUploadIntegration(t *testing.T) { if tc.dataType == v1.DataType_DATA_TYPE_TABULAR_SENSOR { config, deps = setupConfig(t, r, enabledTabularCollectorConfigPath) } else { - r := setupRobot(nil, map[resource.Name]resource.Resource{ + r := setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ camera.Named("c1"): &inject.Camera{ ImageFunc: func( ctx context.Context, From 908426409e58969220f5fda7b40aa7661c72b858 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 7 Nov 2024 10:27:53 -0500 Subject: [PATCH 06/51] Fix up obstacle depth; Delete custom extra type; --- components/camera/collector.go | 2 +- components/camera/extra.go | 22 --------------- components/camera/extra_test.go | 27 ------------------- robot/impl/local_robot_test.go | 2 +- .../vision/obstaclesdepth/obstacles_depth.go | 17 +++--------- 5 files changed, 6 insertions(+), 64 deletions(-) delete mode 100644 components/camera/extra.go delete mode 100644 components/camera/extra_test.go diff --git a/components/camera/collector.go b/components/camera/collector.go index c6e036ab7a0..78580727135 100644 --- a/components/camera/collector.go +++ b/components/camera/collector.go @@ -99,7 +99,7 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d if err := mimeType.UnmarshalTo(mimeStr); err != nil { return nil, err } - img, _, err := camera.Image(ctx, mimeStr.Value, Extra{}) + img, _, err := camera.Image(ctx, mimeStr.Value, nil) if err != nil { // A modular filter component can be created to filter the readings from a component. The error ErrNoCaptureToStore // is used in the datamanager to exclude readings from being captured and stored. diff --git a/components/camera/extra.go b/components/camera/extra.go deleted file mode 100644 index b3e80316a94..00000000000 --- a/components/camera/extra.go +++ /dev/null @@ -1,22 +0,0 @@ -package camera - -import "context" - -// Extra is the type used to represent the extra param for camera methods. -type ( - Extra map[string]interface{} - key int -) - -var extraKey key - -// NewContext returns a new Context that carries value Extra. -func NewContext(ctx context.Context, e Extra) context.Context { - return context.WithValue(ctx, extraKey, e) -} - -// FromContext returns the Extra value stored in ctx, if any. -func FromContext(ctx context.Context) (Extra, bool) { - ext, ok := ctx.Value(extraKey).(Extra) - return ext, ok -} diff --git a/components/camera/extra_test.go b/components/camera/extra_test.go deleted file mode 100644 index be0f0a3f81a..00000000000 --- a/components/camera/extra_test.go +++ /dev/null @@ -1,27 +0,0 @@ -package camera - -import ( - "context" - "testing" - - "go.viam.com/test" -) - -func TestExtraEmpty(t *testing.T) { - ctx := context.Background() - _, ok := FromContext(ctx) - test.That(t, ok, test.ShouldBeFalse) -} - -func TestExtraRoundtrip(t *testing.T) { - ctx := context.Background() - expected := Extra{ - "It goes one": "by one", - "even two": "by two", - } - - ctx = NewContext(ctx, expected) - actual, ok := FromContext(ctx) - test.That(t, ok, test.ShouldBeTrue) - test.That(t, actual, test.ShouldEqual, expected) -} diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 650f1b0f1c9..f39b37fd679 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -94,7 +94,7 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - outBytes, mimeType, err := c1.Image(context.Background(), rutils.MimeTypeJPEG, camera.Extra{}) + outBytes, mimeType, err := c1.Image(context.Background(), rutils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldBeNil) pic, err := rimage.DecodeImage(context.Background(), outBytes, mimeType) test.That(t, err, test.ShouldBeNil) diff --git a/services/vision/obstaclesdepth/obstacles_depth.go b/services/vision/obstaclesdepth/obstacles_depth.go index 29d5ebd3ae6..f8bbb019185 100644 --- a/services/vision/obstaclesdepth/obstacles_depth.go +++ b/services/vision/obstaclesdepth/obstacles_depth.go @@ -13,7 +13,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -118,18 +117,14 @@ func (o *obsDepth) buildObsDepth(logger logging.Logger) func( // buildObsDepthNoIntrinsics will return the median depth in the depth map as a Geometry point. func (o *obsDepth) obsDepthNoIntrinsics(ctx context.Context, src camera.VideoSource) ([]*vision.Object, error) { - ext, ok := camera.FromContext(ctx) - if !ok { - ext = camera.Extra{} - } - imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), ext) + imgBytes, mimeType, err := src.Image(ctx, utils.MimeTypeRawDepth, nil) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } pic, err := rimage.DecodeImage(ctx, imgBytes, mimeType) if err != nil { - return nil, errors.Errorf("could not decode image from %s", src) + return nil, errors.New("could not decode image from obstacle depth source(1)") } dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { @@ -157,17 +152,13 @@ func (o *obsDepth) obsDepthWithIntrinsics(ctx context.Context, src camera.VideoS if o.intrinsics == nil { return nil, errors.New("tried to build obstacles depth with intrinsics but no instrinsics found") } - ext, ok := camera.FromContext(ctx) - if !ok { - ext = camera.Extra{} - } - imgBytes, mimeType, err := src.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), ext) + imgBytes, mimeType, err := src.Image(ctx, utils.MimeTypeRawDepth, nil) if err != nil { return nil, errors.Errorf("could not get image from %s", src) } pic, err := rimage.DecodeImage(ctx, imgBytes, mimeType) if err != nil { - return nil, errors.Errorf("could not decode image from %s", src) + return nil, errors.New("could not decode image from obstacle depth source(2)") } dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { From c44afa2e26ba4ab4f0d021b279212ee54fd4f6cf Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 7 Nov 2024 16:17:44 -0500 Subject: [PATCH 07/51] Update video source comment spec; Add helper to DRY up .Image calls where we convert to go image; Change default mimetypes for classifier --- components/camera/camera.go | 29 ++++++++++++++++++- components/camera/camera_test.go | 8 ++--- components/camera/client.go | 11 +++---- components/camera/client_test.go | 16 +++------- components/camera/fake/camera_test.go | 21 ++++++-------- components/camera/fake/image_file_test.go | 5 +--- robot/client/client_test.go | 4 +-- robot/impl/local_robot_test.go | 5 +--- .../datamanager/builtin/builtin_sync_test.go | 6 ++-- services/datamanager/builtin/builtin_test.go | 2 +- .../vision/obstaclesdepth/obstacles_depth.go | 19 ++++-------- services/vision/vision.go | 24 ++++----------- testutils/inject/camera.go | 4 +-- 13 files changed, 69 insertions(+), 85 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 81052b4da2e..7ffecbcb238 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -6,6 +6,7 @@ package camera import ( "context" + "fmt" "image" "github.com/pkg/errors" @@ -15,6 +16,7 @@ import ( "go.viam.com/rdk/gostream" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/robot" ) @@ -76,9 +78,21 @@ type Camera interface { VideoSource } -// A VideoSource represents anything that can capture frames. +// VideoSource represents anything that can capture frames. // For more information, see the [camera component docs]. // +// Image example: +// +// myCamera, err := camera.FromRobot(machine, "my_camera") +// +// // gets an image from the camera +// imageBytes, mimeType, err := myCamera.Image(context.Background(), utils.MimeTypeJPEG, nil) +// +// Or try to directly decode into an image.Image: +// +// myCamera, err := camera.FromRobot(machine, "my_camera") +// img, err = camera.GetGoImage(context.Background(), utils.MimeTypeJPEG, nil, myCamera) +// // Images example: // // myCamera, err := camera.FromRobot(machine, "my_camera") @@ -140,6 +154,19 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func return gostream.ReadImage(ctx, src) } +// GetGoImage retrieves frame bytes from a camera source and decodes it into an image.Image type. +func GetGoImage(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { + resBytes, resMimeType, err := cam.Image(context.Background(), mimeType, nil) + if err != nil { + return nil, fmt.Errorf("could not get image bytes from camera: %w", err) + } + img, err := rimage.DecodeImage(context.Background(), resBytes, resMimeType) + if err != nil { + return nil, fmt.Errorf("could not decode into image.Image: %w", err) + } + return img, nil +} + // A PointCloudSource is a source that can generate pointclouds. type PointCloudSource interface { NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index d4c8bd2b5d7..cd1bd2d8734 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -182,9 +182,7 @@ func TestCameraWithNoProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - imgBytes, mimeType, err := noProj2.Image(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil) - test.That(t, err, test.ShouldBeNil) - img, err := rimage.DecodeImage(context.Background(), imgBytes, mimeType) + img, err := camera.GetGoImage(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) @@ -231,9 +229,7 @@ func TestCameraWithProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - imgBytes, mimeType, err := cam2.Image(context.Background(), rutils.MimeTypePNG, nil) - test.That(t, err, test.ShouldBeNil) - img, err := rimage.DecodeImage(context.Background(), imgBytes, mimeType) + img, err := camera.GetGoImage(context.Background(), rutils.MimeTypePNG, nil, cam2) test.That(t, err, test.ShouldBeNil) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/client.go b/components/camera/client.go index a720b2c402e..ccc4e7bdf83 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -128,7 +128,8 @@ func (c *client) Stream( // with those from the new "generation". healthyClientCh := c.maybeResetHealthyClientCh() - ctxWithMIME := gostream.WithMIMETypeHint(context.Background(), gostream.MIMETypeHint(ctx, "")) + mimeTypeFromCtx := gostream.MIMETypeHint(ctx, "") + ctxWithMIME := gostream.WithMIMETypeHint(context.Background(), mimeTypeFromCtx) streamCtx, stream, frameCh := gostream.NewMediaStreamForChannel[image.Image](ctxWithMIME) c.activeBackgroundWorkers.Add(1) @@ -145,14 +146,14 @@ func (c *client) Stream( return } - frame, mimeType, err := c.Image(streamCtx, gostream.MIMETypeHint(ctx, ""), nil) + resBytes, resMimeType, err := c.Image(streamCtx, mimeTypeFromCtx, nil) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) } } - img, err := rimage.DecodeImage(ctx, frame, mimeType) + img, err := rimage.DecodeImage(ctx, resBytes, resMimeType) if err != nil { c.logger.CWarnw(ctx, "error decoding image", "err", err) return @@ -183,14 +184,14 @@ func (c *client) Image(ctx context.Context, mimeType string, extra map[string]in defer span.End() expectedType, _ := utils.CheckLazyMIMEType(mimeType) - structExtra, err := goprotoutils.StructToStructPb(extra) + convertedExtra, err := goprotoutils.StructToStructPb(extra) if err != nil { return nil, "", err } resp, err := c.client.GetImage(ctx, &pb.GetImageRequest{ Name: c.name, MimeType: expectedType, - Extra: structExtra, + Extra: convertedExtra, }) if err != nil { return nil, "", err diff --git a/components/camera/client_test.go b/components/camera/client_test.go index b5ee5a8542b..2fc5bbe1098 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -171,9 +171,7 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - frameBytes, mimeType, err := camera1Client.Image(context.Background(), rutils.MimeTypeRawRGBA, nil) - test.That(t, err, test.ShouldBeNil) - frame, err := rimage.DecodeImage(context.Background(), frameBytes, mimeType) + frame, err := camera.GetGoImage(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) @@ -220,9 +218,7 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frameBytes, mimeType, err := client.Image(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil) - test.That(t, err, test.ShouldBeNil) - frame, err := rimage.DecodeImage(context.Background(), frameBytes, mimeType) + frame, err := camera.GetGoImage(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) @@ -463,9 +459,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frameBytes, mimeType, err := camera1Client.Image(ctx, rutils.MimeTypePNG, nil) - test.That(t, err, test.ShouldBeNil) - frame, err := rimage.DecodeImage(ctx, frameBytes, mimeType) + frame, err := camera.GetGoImage(ctx, rutils.MimeTypePNG, nil, camera1Client) test.That(t, err, test.ShouldBeNil) // Should always lazily decode test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) @@ -473,9 +467,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) ctx = context.Background() - frameBytes, mimeType, err = camera1Client.Image(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil) - test.That(t, err, test.ShouldBeNil) - frame, err = rimage.DecodeImage(ctx, frameBytes, mimeType) + frame, err = camera.GetGoImage(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) test.That(t, err, test.ShouldBeNil) test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) frameLazy = frame.(*rimage.LazyEncodedImage) diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index e9536fc853c..505c7c1f7b1 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -15,7 +15,6 @@ import ( "go.viam.com/rdk/components/camera/rtppassthrough" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" - "go.viam.com/rdk/rimage" "go.viam.com/rdk/utils" ) @@ -92,24 +91,22 @@ func TestRTPPassthrough(t *testing.T) { _, err := cfg.Validate("", camera.API.SubtypeName) test.That(t, err, test.ShouldBeNil) - camera, err := NewCamera(context.Background(), nil, cfg, logger) + cam, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) - imgBytes, mimeType, err := camera.Image(context.Background(), utils.MimeTypeRawRGBA, nil) - test.That(t, err, test.ShouldBeNil) - img, err := rimage.DecodeImage(context.Background(), imgBytes, mimeType) + img, err := camera.GetGoImage(context.Background(), utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) - test.That(t, camera, test.ShouldNotBeNil) + test.That(t, cam, test.ShouldNotBeNil) // implements rtppassthrough.Source - cam, ok := camera.(rtppassthrough.Source) + passthroughCam, ok := cam.(rtppassthrough.Source) test.That(t, ok, test.ShouldBeTrue) var called atomic.Bool pktChan := make(chan []*rtp.Packet) // SubscribeRTP succeeds - sub, err := cam.SubscribeRTP(context.Background(), 512, func(pkts []*rtp.Packet) { + sub, err := passthroughCam.SubscribeRTP(context.Background(), 512, func(pkts []*rtp.Packet) { if called.Load() { return } @@ -121,19 +118,19 @@ func TestRTPPassthrough(t *testing.T) { test.That(t, len(pkts), test.ShouldEqual, 4) // Unsubscribe fails when provided an ID for which there is no subscription - test.That(t, cam.Unsubscribe(context.Background(), uuid.New()), test.ShouldBeError, errors.New("id not found")) + test.That(t, passthroughCam.Unsubscribe(context.Background(), uuid.New()), test.ShouldBeError, errors.New("id not found")) test.That(t, sub.Terminated.Err(), test.ShouldBeNil) // Unsubscribe succeeds when provided an ID for which there is a subscription - test.That(t, cam.Unsubscribe(context.Background(), sub.ID), test.ShouldBeNil) + test.That(t, passthroughCam.Unsubscribe(context.Background(), sub.ID), test.ShouldBeNil) // Unsubscribe cancels the subscription test.That(t, sub.Terminated.Err(), test.ShouldBeError, context.Canceled) // subscriptions are cleaned up after Close is called - sub2, err := cam.SubscribeRTP(context.Background(), 512, func(pkts []*rtp.Packet) {}) + sub2, err := passthroughCam.SubscribeRTP(context.Background(), 512, func(pkts []*rtp.Packet) {}) test.That(t, err, test.ShouldBeNil) test.That(t, sub2.Terminated.Err(), test.ShouldBeNil) - test.That(t, camera.Close(context.Background()), test.ShouldBeNil) + test.That(t, cam.Close(context.Background()), test.ShouldBeNil) test.That(t, sub2.Terminated.Err(), test.ShouldBeError, context.Canceled) }) diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index d22cb7c919b..e427f87fe02 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -102,10 +102,7 @@ func TestColorOddResolution(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - imgBytes, _, err := cam.Image(ctx, utils.MimeTypeRawRGBA, nil) - test.That(t, err, test.ShouldBeNil) - - strmImg, err := rimage.DecodeImage(ctx, imgBytes, utils.MimeTypeRawRGBA) + strmImg, err := camera.GetGoImage(ctx, utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) expectedBounds := image.Rect(0, 0, img.Bounds().Dx()-1, img.Bounds().Dy()-1) diff --git a/robot/client/client_test.go b/robot/client/client_test.go index a244849af96..7a2025de75b 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -584,9 +584,7 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - frameBytes, mimeType, err := camera1.Image(context.Background(), rutils.MimeTypeRawRGBA, nil) - test.That(t, err, test.ShouldBeNil) - frame, err := rimage.DecodeImage(context.Background(), frameBytes, mimeType) + frame, err := camera.GetGoImage(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index f39b37fd679..67bb79f051c 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -58,7 +58,6 @@ import ( "go.viam.com/rdk/protoutils" "go.viam.com/rdk/referenceframe" "go.viam.com/rdk/resource" - "go.viam.com/rdk/rimage" "go.viam.com/rdk/robot" "go.viam.com/rdk/robot/client" "go.viam.com/rdk/robot/framesystem" @@ -94,9 +93,7 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - outBytes, mimeType, err := c1.Image(context.Background(), rutils.MimeTypeJPEG, nil) - test.That(t, err, test.ShouldBeNil) - pic, err := rimage.DecodeImage(context.Background(), outBytes, mimeType) + pic, err := camera.GetGoImage(context.Background(), rutils.MimeTypeJPEG, nil, c1) test.That(t, err, test.ShouldBeNil) bounds := pic.Bounds() diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index 09270c93f0a..fa0ec791943 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -370,7 +370,7 @@ func TestDataCaptureUploadIntegration(t *testing.T) { if err != nil { return nil, "", err } - return outBytes, "", nil + return outBytes, mimeType, nil }, }, }) @@ -777,7 +777,7 @@ func TestStreamingDCUpload(t *testing.T) { if err != nil { return nil, "", err } - return outBytes, "", nil + return outBytes, mimeType, nil }, }, }) @@ -1022,7 +1022,7 @@ func TestSyncConfigUpdateBehavior(t *testing.T) { if err != nil { return nil, "", err } - return outBytes, "", nil + return outBytes, mimeType, nil }, }, }) diff --git a/services/datamanager/builtin/builtin_test.go b/services/datamanager/builtin/builtin_test.go index e991d1ca7c3..1a3bacc47fc 100644 --- a/services/datamanager/builtin/builtin_test.go +++ b/services/datamanager/builtin/builtin_test.go @@ -458,7 +458,7 @@ func TestSync(t *testing.T) { if err != nil { return nil, "", err } - return outBytes, "", nil + return outBytes, mimeType, nil }, }, }) diff --git a/services/vision/obstaclesdepth/obstacles_depth.go b/services/vision/obstaclesdepth/obstacles_depth.go index f8bbb019185..f0adc8584c8 100644 --- a/services/vision/obstaclesdepth/obstacles_depth.go +++ b/services/vision/obstaclesdepth/obstacles_depth.go @@ -6,6 +6,7 @@ package obstaclesdepth import ( "context" + "fmt" "sort" "github.com/golang/geo/r3" @@ -13,6 +14,7 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -117,14 +119,9 @@ func (o *obsDepth) buildObsDepth(logger logging.Logger) func( // buildObsDepthNoIntrinsics will return the median depth in the depth map as a Geometry point. func (o *obsDepth) obsDepthNoIntrinsics(ctx context.Context, src camera.VideoSource) ([]*vision.Object, error) { - imgBytes, mimeType, err := src.Image(ctx, utils.MimeTypeRawDepth, nil) + pic, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), nil, src) if err != nil { - return nil, errors.Errorf("could not get image from %s", src) - } - - pic, err := rimage.DecodeImage(ctx, imgBytes, mimeType) - if err != nil { - return nil, errors.New("could not decode image from obstacle depth source(1)") + return nil, fmt.Errorf("obstacle depth source (no intrinsics) error: %w", err) } dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { @@ -152,13 +149,9 @@ func (o *obsDepth) obsDepthWithIntrinsics(ctx context.Context, src camera.VideoS if o.intrinsics == nil { return nil, errors.New("tried to build obstacles depth with intrinsics but no instrinsics found") } - imgBytes, mimeType, err := src.Image(ctx, utils.MimeTypeRawDepth, nil) - if err != nil { - return nil, errors.Errorf("could not get image from %s", src) - } - pic, err := rimage.DecodeImage(ctx, imgBytes, mimeType) + pic, err := camera.GetGoImage(ctx, utils.MimeTypeRawDepth, nil, src) if err != nil { - return nil, errors.New("could not decode image from obstacle depth source(2)") + return nil, fmt.Errorf("obstacle depth source (with intrinsics) error: %w", err) } dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { diff --git a/services/vision/vision.go b/services/vision/vision.go index f7dcecc8be1..732ec9c26be 100644 --- a/services/vision/vision.go +++ b/services/vision/vision.go @@ -17,9 +17,7 @@ import ( "go.viam.com/rdk/data" "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" - "go.viam.com/rdk/rimage" "go.viam.com/rdk/robot" - "go.viam.com/rdk/utils" viz "go.viam.com/rdk/vision" "go.viam.com/rdk/vision/classification" "go.viam.com/rdk/vision/objectdetection" @@ -311,13 +309,9 @@ func (vm *vizModel) DetectionsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - imgBytes, mimeType, err := cam.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) if err != nil { - return nil, errors.Wrapf(err, "could not get image from %s", cameraName) - } - img, err := rimage.DecodeImage(ctx, imgBytes, mimeType) - if err != nil { - return nil, errors.Errorf("could not decode image from %s", cameraName) + return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } return vm.detectorFunc(ctx, img) } @@ -357,13 +351,9 @@ func (vm *vizModel) ClassificationsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - imgBytes, mimeType, err := cam.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra) - if err != nil { - return nil, errors.Wrapf(err, "could not get image from %s", cameraName) - } - img, err := rimage.DecodeImage(ctx, imgBytes, mimeType) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) if err != nil { - return nil, errors.Errorf("could not decode image from %s", cameraName) + return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } fullClassifications, err := vm.classifierFunc(ctx, img) if err != nil { @@ -410,14 +400,10 @@ func (vm *vizModel) CaptureAllFromCamera( if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not find camera named %s", cameraName) } - imgBytes, mimeType, err := cam.Image(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not get image from %s", cameraName) } - img, err := rimage.DecodeImage(ctx, imgBytes, mimeType) - if err != nil { - return viscapture.VisCapture{}, errors.Errorf("could not decode image from %s", cameraName) - } logger := vm.r.Logger() var detections []objectdetection.Detection if opt.ReturnDetections { diff --git a/testutils/inject/camera.go b/testutils/inject/camera.go index 9d87129cf6f..b67659fa25b 100644 --- a/testutils/inject/camera.go +++ b/testutils/inject/camera.go @@ -19,12 +19,12 @@ type Camera struct { name resource.Name RTPPassthroughSource rtppassthrough.Source DoFunc func(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error) + ImageFunc func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) + ImagesFunc func(ctx context.Context) ([]camera.NamedImage, resource.ResponseMetadata, error) StreamFunc func( ctx context.Context, errHandlers ...gostream.ErrorHandler, ) (gostream.VideoStream, error) - ImagesFunc func(ctx context.Context) ([]camera.NamedImage, resource.ResponseMetadata, error) - ImageFunc func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) NextPointCloudFunc func(ctx context.Context) (pointcloud.PointCloud, error) ProjectorFunc func(ctx context.Context) (transform.Projector, error) PropertiesFunc func(ctx context.Context) (camera.Properties, error) From 11b1d7d567c22fb428f3245a46a53f0b5fbff1a1 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 7 Nov 2024 16:42:35 -0500 Subject: [PATCH 08/51] Fix obstacle depth mimetype (it needs it for re-encode since we can't encode "") --- services/vision/obstaclesdepth/obstacles_depth.go | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/services/vision/obstaclesdepth/obstacles_depth.go b/services/vision/obstaclesdepth/obstacles_depth.go index f0adc8584c8..0b49b69b5b1 100644 --- a/services/vision/obstaclesdepth/obstacles_depth.go +++ b/services/vision/obstaclesdepth/obstacles_depth.go @@ -119,7 +119,7 @@ func (o *obsDepth) buildObsDepth(logger logging.Logger) func( // buildObsDepthNoIntrinsics will return the median depth in the depth map as a Geometry point. func (o *obsDepth) obsDepthNoIntrinsics(ctx context.Context, src camera.VideoSource) ([]*vision.Object, error) { - pic, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), nil, src) + pic, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), nil, src) if err != nil { return nil, fmt.Errorf("obstacle depth source (no intrinsics) error: %w", err) } @@ -149,7 +149,7 @@ func (o *obsDepth) obsDepthWithIntrinsics(ctx context.Context, src camera.VideoS if o.intrinsics == nil { return nil, errors.New("tried to build obstacles depth with intrinsics but no instrinsics found") } - pic, err := camera.GetGoImage(ctx, utils.MimeTypeRawDepth, nil, src) + pic, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), nil, src) if err != nil { return nil, fmt.Errorf("obstacle depth source (with intrinsics) error: %w", err) } From 438d5506f2d3e7732dc41697fab48c9bcf910a82 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 7 Nov 2024 17:07:56 -0500 Subject: [PATCH 09/51] Add image metadata replacing mimetype return; Add back non empty string default mimetypes for vision since we are failing unit tests with 'do not know how to encode' errors --- components/camera/camera.go | 13 ++++-- components/camera/client.go | 12 +++--- components/camera/client_test.go | 42 ++++++++++--------- components/camera/replaypcd/replaypcd.go | 4 +- components/camera/server.go | 6 +-- components/camera/server_test.go | 38 +++++++++-------- components/camera/videosource/webcam.go | 8 ++-- components/camera/videosourcewrappers.go | 8 ++-- robot/client/client_test.go | 4 +- .../datamanager/builtin/builtin_sync_test.go | 24 +++++------ services/datamanager/builtin/builtin_test.go | 6 +-- services/vision/vision.go | 7 ++-- testutils/inject/camera.go | 6 +-- 13 files changed, 96 insertions(+), 82 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 7ffecbcb238..82b0dd1dd19 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -72,6 +72,11 @@ type NamedImage struct { SourceName string } +// ImageMetadata contains useful information about returned image bytes such as its mimetype. +type ImageMetadata struct { + MimeType string +} + // A Camera is a resource that can capture frames. type Camera interface { resource.Resource @@ -127,7 +132,7 @@ type Camera interface { type VideoSource interface { // Image returns a byte slice representing an image that tries to adhere to the MIME type hint. // Image also may return a string representing the mime type hint or empty string if not. - Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) + Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) // Images is used for getting simultaneous images from different imagers, // along with associated metadata (just timestamp for now). It's not for getting a time series of images from the same imager. @@ -154,13 +159,13 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func return gostream.ReadImage(ctx, src) } -// GetGoImage retrieves frame bytes from a camera source and decodes it into an image.Image type. +// GetGoImage retrieves image bytes from a camera source and decodes it into an image.Image type. func GetGoImage(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { - resBytes, resMimeType, err := cam.Image(context.Background(), mimeType, nil) + resBytes, resMetadata, err := cam.Image(context.Background(), mimeType, nil) if err != nil { return nil, fmt.Errorf("could not get image bytes from camera: %w", err) } - img, err := rimage.DecodeImage(context.Background(), resBytes, resMimeType) + img, err := rimage.DecodeImage(context.Background(), resBytes, resMetadata.MimeType) if err != nil { return nil, fmt.Errorf("could not decode into image.Image: %w", err) } diff --git a/components/camera/client.go b/components/camera/client.go index ccc4e7bdf83..93a0f4907ee 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -146,14 +146,14 @@ func (c *client) Stream( return } - resBytes, resMimeType, err := c.Image(streamCtx, mimeTypeFromCtx, nil) + resBytes, resMetadata, err := c.Image(streamCtx, mimeTypeFromCtx, nil) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) } } - img, err := rimage.DecodeImage(ctx, resBytes, resMimeType) + img, err := rimage.DecodeImage(ctx, resBytes, resMetadata.MimeType) if err != nil { c.logger.CWarnw(ctx, "error decoding image", "err", err) return @@ -179,14 +179,14 @@ func (c *client) Stream( return stream, nil } -func (c *client) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { +func (c *client) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) { ctx, span := trace.StartSpan(ctx, "camera::client::Image") defer span.End() expectedType, _ := utils.CheckLazyMIMEType(mimeType) convertedExtra, err := goprotoutils.StructToStructPb(extra) if err != nil { - return nil, "", err + return nil, ImageMetadata{}, err } resp, err := c.client.GetImage(ctx, &pb.GetImageRequest{ Name: c.name, @@ -194,7 +194,7 @@ func (c *client) Image(ctx context.Context, mimeType string, extra map[string]in Extra: convertedExtra, }) if err != nil { - return nil, "", err + return nil, ImageMetadata{}, err } if expectedType != "" && resp.MimeType != expectedType { @@ -204,7 +204,7 @@ func (c *client) Image(ctx context.Context, mimeType string, extra map[string]in } resp.MimeType = utils.WithLazyMIMEType(resp.MimeType) - return resp.Image, resp.MimeType, nil + return resp.Image, ImageMetadata{MimeType: resp.MimeType}, nil } func (c *client) Images(ctx context.Context) ([]NamedImage, resource.ResponseMetadata, error) { diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 2fc5bbe1098..2bef77278db 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -96,10 +96,10 @@ func TestClient(t *testing.T) { ts := time.UnixMilli(12345) return images, resource.ResponseMetadata{CapturedAt: ts}, nil } - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) test.That(t, err, test.ShouldBeNil) - return resBytes, mimeType, nil + return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil } // depth camera injectCameraDepth := &inject.Camera{} @@ -121,10 +121,14 @@ func TestClient(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCameraDepth.ImageFunc = func( + ctx context.Context, + mimeType string, + extra map[string]interface{}, + ) ([]byte, camera.ImageMetadata, error) { resBytes, err := rimage.EncodeImage(ctx, depthImg, mimeType) test.That(t, err, test.ShouldBeNil) - return resBytes, mimeType, nil + return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil } // bad camera injectCamera2 := &inject.Camera{} @@ -137,8 +141,8 @@ func TestClient(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { - return nil, mimeType, errGetImageFailed + injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + return nil, camera.ImageMetadata{}, errGetImageFailed } resources := map[resource.Name]camera.Camera{ @@ -255,9 +259,9 @@ func TestClient(t *testing.T) { camClient, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, extra, test.ShouldBeEmpty) - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } ctx := context.Background() @@ -265,10 +269,10 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra["hello"], test.ShouldEqual, "world") - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } // one kvp created with map[string]interface{} @@ -277,22 +281,22 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } _, _, err = camClient.Image(context.Background(), "", map[string]interface{}{data.FromDMString: true}) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, len(extra), test.ShouldEqual, 2) test.That(t, extra["hello"], test.ShouldEqual, "world") test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } // merge values from data and camera @@ -425,7 +429,7 @@ func TestClientLazyImage(t *testing.T) { imgPng, err := png.Decode(bytes.NewReader(imgBuf.Bytes())) test.That(t, err, test.ShouldBeNil) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { if mimeType == "" { mimeType = rutils.MimeTypeRawRGBA } @@ -434,9 +438,9 @@ func TestClientLazyImage(t *testing.T) { case rutils.MimeTypePNG: resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) test.That(t, err, test.ShouldBeNil) - return resBytes, mimeType, nil + return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil default: - return nil, mimeType, errInvalidMimeType + return nil, camera.ImageMetadata{}, errInvalidMimeType } } @@ -557,10 +561,10 @@ func TestClientStreamAfterClose(t *testing.T) { injectCamera.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) test.That(t, err, test.ShouldBeNil) - return imgBytes, mimeType, nil + return imgBytes, camera.ImageMetadata{MimeType: mimeType}, nil } // Register CameraService API in our gRPC server. diff --git a/components/camera/replaypcd/replaypcd.go b/components/camera/replaypcd/replaypcd.go index 2b00daa5899..fb5e0f0257e 100644 --- a/components/camera/replaypcd/replaypcd.go +++ b/components/camera/replaypcd/replaypcd.go @@ -346,8 +346,8 @@ func (replay *pcdCamera) Stream(ctx context.Context, errHandlers ...gostream.Err return stream, errors.New("Stream is unimplemented") } -func (replay *pcdCamera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { - return nil, "", errors.New("Image is unimplemented") +func (replay *pcdCamera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + return nil, camera.ImageMetadata{}, errors.New("Image is unimplemented") } // Close stops replay camera, closes the channels and its connections to the cloud. diff --git a/components/camera/server.go b/components/camera/server.go index 603ed40d63e..6874803ff04 100644 --- a/components/camera/server.go +++ b/components/camera/server.go @@ -70,12 +70,12 @@ func (s *serviceServer) GetImage( } req.MimeType = utils.WithLazyMIMEType(req.MimeType) - imgBytes, mimeType, err := cam.Image(ctx, req.MimeType, req.Extra.AsMap()) + resBytes, resMetadata, err := cam.Image(ctx, req.MimeType, req.Extra.AsMap()) if err != nil { return nil, err } - actualMIME, _ := utils.CheckLazyMIMEType(mimeType) - return &pb.GetImageResponse{MimeType: actualMIME, Image: imgBytes}, nil + actualMIME, _ := utils.CheckLazyMIMEType(resMetadata.MimeType) + return &pb.GetImageResponse{MimeType: actualMIME, Image: resBytes}, nil } // GetImages returns a list of images and metadata from a camera of the underlying robot. diff --git a/components/camera/server_test.go b/components/camera/server_test.go index fb47842bf34..a4eaeeaa41d 100644 --- a/components/camera/server_test.go +++ b/components/camera/server_test.go @@ -108,7 +108,7 @@ func TestServer(t *testing.T) { return projA, nil } wooMIME := "image/woohoo" - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { if mimeType == "" { mimeType = utils.MimeTypeRawRGBA } @@ -125,13 +125,13 @@ func TestServer(t *testing.T) { case "image/woohoo": respImg = rimage.NewLazyEncodedImage([]byte{1, 2, 3}, mimeType) default: - return nil, "", errInvalidMimeType + return nil, camera.ImageMetadata{}, errInvalidMimeType } resBytes, err := rimage.EncodeImage(ctx, respImg, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return resBytes, mimeType, nil + return resBytes, camera.ImageMetadata{}, nil } // depth camera depthImage := rimage.NewEmptyDepthMap(10, 20) @@ -156,12 +156,16 @@ func TestServer(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCameraDepth.ImageFunc = func( + ctx context.Context, + mimeType string, + extra map[string]interface{}, + ) ([]byte, camera.ImageMetadata, error) { resBytes, err := rimage.EncodeImage(ctx, depthImage, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return resBytes, mimeType, nil + return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil } // bad camera injectCamera2.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { @@ -173,8 +177,8 @@ func TestServer(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { - return nil, "", errGetImageFailed + injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + return nil, camera.ImageMetadata{}, errGetImageFailed } // does a depth camera transfer its depth image properly @@ -389,9 +393,9 @@ func TestServer(t *testing.T) { }) t.Run("GetImage with extra", func(t *testing.T) { - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, extra, test.ShouldBeEmpty) - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ @@ -401,10 +405,10 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra["hello"], test.ShouldEqual, "world") - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } ext, err := goprotoutils.StructToStructPb(map[string]interface{}{"hello": "world"}) @@ -418,11 +422,11 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, len(extra), test.ShouldEqual, 1) test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } // one kvp created with data.FromDMContextKey @@ -437,11 +441,11 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { test.That(t, len(extra), test.ShouldEqual, 2) test.That(t, extra["hello"], test.ShouldEqual, "world") test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, "", errGetImageFailed + return nil, camera.ImageMetadata{}, errGetImageFailed } // use values from data and camera diff --git a/components/camera/videosource/webcam.go b/components/camera/videosource/webcam.go index 5703063fffb..fee94b31de5 100644 --- a/components/camera/videosource/webcam.go +++ b/components/camera/videosource/webcam.go @@ -566,17 +566,17 @@ func (c *monitoredWebcam) Stream(ctx context.Context, errHandlers ...gostream.Er return c.exposedSwapper.Stream(ctx, errHandlers...) } -func (c *monitoredWebcam) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { +func (c *monitoredWebcam) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { img, release, err := camera.ReadImage(ctx, c.underlyingSource) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } defer release() imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return imgBytes, mimeType, nil + return imgBytes, camera.ImageMetadata{MimeType: mimeType}, nil } func (c *monitoredWebcam) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { diff --git a/components/camera/videosourcewrappers.go b/components/camera/videosourcewrappers.go index a9ee5eb6d4a..48ef60c6269 100644 --- a/components/camera/videosourcewrappers.go +++ b/components/camera/videosourcewrappers.go @@ -197,17 +197,17 @@ func (vs *videoSource) Stream(ctx context.Context, errHandlers ...gostream.Error return vs.videoSource.Stream(ctx, errHandlers...) } -func (vs *videoSource) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { +func (vs *videoSource) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) { img, release, err := ReadImage(ctx, vs.videoSource) if err != nil { - return nil, "", err + return nil, ImageMetadata{}, err } defer release() outBytes, err := rimage.EncodeImage(ctx, img, mimeType) if err != nil { - return nil, "", err + return nil, ImageMetadata{}, err } - return outBytes, mimeType, nil + return outBytes, ImageMetadata{MimeType: mimeType}, nil } // Images is for getting simultaneous images from different sensors diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 7a2025de75b..71b3b5571fd 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -331,10 +331,10 @@ func TestStatusClient(t *testing.T) { var imgBuf bytes.Buffer test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { + injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { resBytes, err := rimage.EncodeImage(ctx, img, mimeType) test.That(t, err, test.ShouldBeNil) - return resBytes, mimeType, nil + return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil } injectInputDev := &inject.InputController{} diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index fa0ec791943..b212c50ab4e 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -158,12 +158,12 @@ func TestSyncEnabled(t *testing.T) { ctx context.Context, mimeType string, extra map[string]interface{}, - ) ([]byte, string, error) { + ) ([]byte, camera.ImageMetadata, error) { outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return outBytes, mimeType, nil + return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil }, }, }) @@ -365,12 +365,12 @@ func TestDataCaptureUploadIntegration(t *testing.T) { ctx context.Context, mimeType string, extra map[string]interface{}, - ) ([]byte, string, error) { + ) ([]byte, camera.ImageMetadata, error) { outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return outBytes, mimeType, nil + return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil }, }, }) @@ -772,12 +772,12 @@ func TestStreamingDCUpload(t *testing.T) { ctx context.Context, mimeType string, extra map[string]interface{}, - ) ([]byte, string, error) { + ) ([]byte, camera.ImageMetadata, error) { outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return outBytes, mimeType, nil + return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil }, }, }) @@ -1017,12 +1017,12 @@ func TestSyncConfigUpdateBehavior(t *testing.T) { ctx context.Context, mimeType string, extra map[string]interface{}, - ) ([]byte, string, error) { + ) ([]byte, camera.ImageMetadata, error) { outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return outBytes, mimeType, nil + return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil }, }, }) diff --git a/services/datamanager/builtin/builtin_test.go b/services/datamanager/builtin/builtin_test.go index 1a3bacc47fc..503c8861b88 100644 --- a/services/datamanager/builtin/builtin_test.go +++ b/services/datamanager/builtin/builtin_test.go @@ -453,12 +453,12 @@ func TestSync(t *testing.T) { ctx context.Context, mimeType string, extra map[string]interface{}, - ) ([]byte, string, error) { + ) ([]byte, camera.ImageMetadata, error) { outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) if err != nil { - return nil, "", err + return nil, camera.ImageMetadata{}, err } - return outBytes, mimeType, nil + return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil }, }, }) diff --git a/services/vision/vision.go b/services/vision/vision.go index 732ec9c26be..669c91287c4 100644 --- a/services/vision/vision.go +++ b/services/vision/vision.go @@ -18,6 +18,7 @@ import ( "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/robot" + "go.viam.com/rdk/utils" viz "go.viam.com/rdk/vision" "go.viam.com/rdk/vision/classification" "go.viam.com/rdk/vision/objectdetection" @@ -309,7 +310,7 @@ func (vm *vizModel) DetectionsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra, cam) if err != nil { return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } @@ -351,7 +352,7 @@ func (vm *vizModel) ClassificationsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra, cam) if err != nil { return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } @@ -400,7 +401,7 @@ func (vm *vizModel) CaptureAllFromCamera( if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra, cam) if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not get image from %s", cameraName) } diff --git a/testutils/inject/camera.go b/testutils/inject/camera.go index b67659fa25b..dc1c03ece94 100644 --- a/testutils/inject/camera.go +++ b/testutils/inject/camera.go @@ -19,7 +19,7 @@ type Camera struct { name resource.Name RTPPassthroughSource rtppassthrough.Source DoFunc func(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error) - ImageFunc func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) + ImageFunc func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) ImagesFunc func(ctx context.Context) ([]camera.NamedImage, resource.ResponseMetadata, error) StreamFunc func( ctx context.Context, @@ -67,14 +67,14 @@ func (c *Camera) Stream( } // Image calls the injected Image or the real version. -func (c *Camera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, string, error) { +func (c *Camera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { if c.ImageFunc != nil { return c.ImageFunc(ctx, mimeType, extra) } if c.Camera != nil { return c.Camera.Image(ctx, mimeType, extra) } - return nil, "", errors.Wrap(ctx.Err(), "no GetImage function available") + return nil, camera.ImageMetadata{}, errors.Wrap(ctx.Err(), "no GetImage function available") } // Properties calls the injected Properties or the real version. From 0d8081b0cfd88533130c502e65497e25a9c7af98 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 7 Nov 2024 17:45:00 -0500 Subject: [PATCH 10/51] Forgot to include mimetype in test resp oops --- components/camera/server_test.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/components/camera/server_test.go b/components/camera/server_test.go index a4eaeeaa41d..9e932c8b969 100644 --- a/components/camera/server_test.go +++ b/components/camera/server_test.go @@ -131,7 +131,7 @@ func TestServer(t *testing.T) { if err != nil { return nil, camera.ImageMetadata{}, err } - return resBytes, camera.ImageMetadata{}, nil + return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil } // depth camera depthImage := rimage.NewEmptyDepthMap(10, 20) From 824c30f2b1e3f0f5b85578f11931ab035721544e Mon Sep 17 00:00:00 2001 From: hexbabe Date: Fri, 8 Nov 2024 15:44:19 -0500 Subject: [PATCH 11/51] Add width and height to ImageMetadata struct --- components/camera/camera.go | 2 ++ 1 file changed, 2 insertions(+) diff --git a/components/camera/camera.go b/components/camera/camera.go index 82b0dd1dd19..3c21d29752a 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -75,6 +75,8 @@ type NamedImage struct { // ImageMetadata contains useful information about returned image bytes such as its mimetype. type ImageMetadata struct { MimeType string + Width int + Height int } // A Camera is a resource that can capture frames. From e744b68f567cecb07a85376e421784505b949937 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Fri, 8 Nov 2024 15:54:01 -0500 Subject: [PATCH 12/51] Use GetGoImage in camera client Stream --- components/camera/client.go | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/components/camera/client.go b/components/camera/client.go index 93a0f4907ee..bc7eb248165 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -146,19 +146,13 @@ func (c *client) Stream( return } - resBytes, resMetadata, err := c.Image(streamCtx, mimeTypeFromCtx, nil) + img, err := GetGoImage(streamCtx, mimeTypeFromCtx, nil, c) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) } } - img, err := rimage.DecodeImage(ctx, resBytes, resMetadata.MimeType) - if err != nil { - c.logger.CWarnw(ctx, "error decoding image", "err", err) - return - } - select { case <-streamCtx.Done(): return From fd50881ed898e13ed2250958db27a98abb2748e2 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Mon, 11 Nov 2024 14:39:04 -0500 Subject: [PATCH 13/51] Remove jpeg default in vision --- services/vision/vision.go | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/services/vision/vision.go b/services/vision/vision.go index 669c91287c4..732ec9c26be 100644 --- a/services/vision/vision.go +++ b/services/vision/vision.go @@ -18,7 +18,6 @@ import ( "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/robot" - "go.viam.com/rdk/utils" viz "go.viam.com/rdk/vision" "go.viam.com/rdk/vision/classification" "go.viam.com/rdk/vision/objectdetection" @@ -310,7 +309,7 @@ func (vm *vizModel) DetectionsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra, cam) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) if err != nil { return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } @@ -352,7 +351,7 @@ func (vm *vizModel) ClassificationsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra, cam) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) if err != nil { return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } @@ -401,7 +400,7 @@ func (vm *vizModel) CaptureAllFromCamera( if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeJPEG), extra, cam) + img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not get image from %s", cameraName) } From e57039393cfff8b97e9dfee2c55d0a507324fd48 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Mon, 11 Nov 2024 16:09:41 -0500 Subject: [PATCH 14/51] Revert detections, classifications, and capture all's image call to ReadImage --- services/vision/vision.go | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/services/vision/vision.go b/services/vision/vision.go index 732ec9c26be..34dbc029254 100644 --- a/services/vision/vision.go +++ b/services/vision/vision.go @@ -15,7 +15,6 @@ import ( "go.viam.com/rdk/components/camera" "go.viam.com/rdk/data" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/resource" "go.viam.com/rdk/robot" viz "go.viam.com/rdk/vision" @@ -309,10 +308,11 @@ func (vm *vizModel) DetectionsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) + img, release, err := camera.ReadImage(ctx, cam) if err != nil { return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } + defer release() return vm.detectorFunc(ctx, img) } @@ -351,10 +351,11 @@ func (vm *vizModel) ClassificationsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) + img, release, err := camera.ReadImage(ctx, cam) if err != nil { return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) } + defer release() fullClassifications, err := vm.classifierFunc(ctx, img) if err != nil { return nil, errors.Wrap(err, "could not get classifications from image") @@ -400,10 +401,11 @@ func (vm *vizModel) CaptureAllFromCamera( if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, ""), extra, cam) + img, release, err := camera.ReadImage(ctx, cam) if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not get image from %s", cameraName) } + defer release() logger := vm.r.Logger() var detections []objectdetection.Detection if opt.ReturnDetections { From 6646d78f489a5f6fd142d24b28bdcdcd15424281 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Tue, 12 Nov 2024 10:56:22 -0500 Subject: [PATCH 15/51] Don't modify vision at all --- services/vision/obstaclesdepth/obstacles_depth.go | 13 +++++++------ services/vision/vision.go | 4 ++-- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/services/vision/obstaclesdepth/obstacles_depth.go b/services/vision/obstaclesdepth/obstacles_depth.go index 0b49b69b5b1..ed450b98d9b 100644 --- a/services/vision/obstaclesdepth/obstacles_depth.go +++ b/services/vision/obstaclesdepth/obstacles_depth.go @@ -6,7 +6,6 @@ package obstaclesdepth import ( "context" - "fmt" "sort" "github.com/golang/geo/r3" @@ -14,7 +13,6 @@ import ( "go.opencensus.io/trace" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -119,10 +117,12 @@ func (o *obsDepth) buildObsDepth(logger logging.Logger) func( // buildObsDepthNoIntrinsics will return the median depth in the depth map as a Geometry point. func (o *obsDepth) obsDepthNoIntrinsics(ctx context.Context, src camera.VideoSource) ([]*vision.Object, error) { - pic, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), nil, src) + pic, release, err := camera.ReadImage(ctx, src) if err != nil { - return nil, fmt.Errorf("obstacle depth source (no intrinsics) error: %w", err) + return nil, errors.Errorf("could not get image from %s", src) } + defer release() + dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { return nil, errors.New("could not convert image to depth map") @@ -149,10 +149,11 @@ func (o *obsDepth) obsDepthWithIntrinsics(ctx context.Context, src camera.VideoS if o.intrinsics == nil { return nil, errors.New("tried to build obstacles depth with intrinsics but no instrinsics found") } - pic, err := camera.GetGoImage(ctx, gostream.MIMETypeHint(ctx, utils.MimeTypeRawDepth), nil, src) + pic, release, err := camera.ReadImage(ctx, src) if err != nil { - return nil, fmt.Errorf("obstacle depth source (with intrinsics) error: %w", err) + return nil, errors.Errorf("could not get image from %s", src) } + defer release() dm, err := rimage.ConvertImageToDepthMap(ctx, pic) if err != nil { return nil, errors.New("could not convert image to depth map") diff --git a/services/vision/vision.go b/services/vision/vision.go index 34dbc029254..e763c31db23 100644 --- a/services/vision/vision.go +++ b/services/vision/vision.go @@ -310,7 +310,7 @@ func (vm *vizModel) DetectionsFromCamera( } img, release, err := camera.ReadImage(ctx, cam) if err != nil { - return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) + return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } defer release() return vm.detectorFunc(ctx, img) @@ -353,7 +353,7 @@ func (vm *vizModel) ClassificationsFromCamera( } img, release, err := camera.ReadImage(ctx, cam) if err != nil { - return nil, errors.Wrapf(err, "could not get go image from %s", cameraName) + return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } defer release() fullClassifications, err := vm.classifierFunc(ctx, img) From 612e91cc06a8cd7da4f24a322294efa49d1b4cc7 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Tue, 12 Nov 2024 11:09:50 -0500 Subject: [PATCH 16/51] Remove width and height from ImageMetadata; DRY up webcam and videosourcewrappers Image func --- components/camera/camera.go | 17 +++++++++++++++-- components/camera/videosource/webcam.go | 12 +----------- components/camera/videosourcewrappers.go | 11 +---------- testutils/inject/camera.go | 2 +- 4 files changed, 18 insertions(+), 24 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 3c21d29752a..e4f9592f471 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -75,8 +75,6 @@ type NamedImage struct { // ImageMetadata contains useful information about returned image bytes such as its mimetype. type ImageMetadata struct { MimeType string - Width int - Height int } // A Camera is a resource that can capture frames. @@ -161,6 +159,21 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func return gostream.ReadImage(ctx, src) } +// ReadImageBytes wraps ReadImage given a mimetype to encode the image as bytes data, returning +// supplementary metadata for downstream processing. +func ReadImageBytes(ctx context.Context, src gostream.VideoSource, mimeType string) ([]byte, ImageMetadata, error) { + img, release, err := ReadImage(ctx, src) + if err != nil { + return nil, ImageMetadata{}, err + } + defer release() + imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) + if err != nil { + return nil, ImageMetadata{}, err + } + return imgBytes, ImageMetadata{MimeType: mimeType}, nil +} + // GetGoImage retrieves image bytes from a camera source and decodes it into an image.Image type. func GetGoImage(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { resBytes, resMetadata, err := cam.Image(context.Background(), mimeType, nil) diff --git a/components/camera/videosource/webcam.go b/components/camera/videosource/webcam.go index fee94b31de5..2c7a6070308 100644 --- a/components/camera/videosource/webcam.go +++ b/components/camera/videosource/webcam.go @@ -28,7 +28,6 @@ import ( "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" - "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" ) @@ -567,16 +566,7 @@ func (c *monitoredWebcam) Stream(ctx context.Context, errHandlers ...gostream.Er } func (c *monitoredWebcam) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - img, release, err := camera.ReadImage(ctx, c.underlyingSource) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - defer release() - imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return imgBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return camera.ReadImageBytes(ctx, c.underlyingSource, mimeType) } func (c *monitoredWebcam) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { diff --git a/components/camera/videosourcewrappers.go b/components/camera/videosourcewrappers.go index 48ef60c6269..0741095e9cd 100644 --- a/components/camera/videosourcewrappers.go +++ b/components/camera/videosourcewrappers.go @@ -198,16 +198,7 @@ func (vs *videoSource) Stream(ctx context.Context, errHandlers ...gostream.Error } func (vs *videoSource) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) { - img, release, err := ReadImage(ctx, vs.videoSource) - if err != nil { - return nil, ImageMetadata{}, err - } - defer release() - outBytes, err := rimage.EncodeImage(ctx, img, mimeType) - if err != nil { - return nil, ImageMetadata{}, err - } - return outBytes, ImageMetadata{MimeType: mimeType}, nil + return ReadImageBytes(ctx, vs.videoSource, mimeType) } // Images is for getting simultaneous images from different sensors diff --git a/testutils/inject/camera.go b/testutils/inject/camera.go index dc1c03ece94..975bb9b58d0 100644 --- a/testutils/inject/camera.go +++ b/testutils/inject/camera.go @@ -74,7 +74,7 @@ func (c *Camera) Image(ctx context.Context, mimeType string, extra map[string]in if c.Camera != nil { return c.Camera.Image(ctx, mimeType, extra) } - return nil, camera.ImageMetadata{}, errors.Wrap(ctx.Err(), "no GetImage function available") + return nil, camera.ImageMetadata{}, errors.Wrap(ctx.Err(), "no Image function available") } // Properties calls the injected Properties or the real version. From 9029a051e28807e54a02ccb13a6245d83d5139d8 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 13 Nov 2024 15:56:29 -0500 Subject: [PATCH 17/51] Move ReadImageBytes to videosourcewrappers --- components/camera/camera.go | 15 --------------- components/camera/videosourcewrappers.go | 16 ++++++++++++++++ 2 files changed, 16 insertions(+), 15 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index e4f9592f471..82b0dd1dd19 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -159,21 +159,6 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func return gostream.ReadImage(ctx, src) } -// ReadImageBytes wraps ReadImage given a mimetype to encode the image as bytes data, returning -// supplementary metadata for downstream processing. -func ReadImageBytes(ctx context.Context, src gostream.VideoSource, mimeType string) ([]byte, ImageMetadata, error) { - img, release, err := ReadImage(ctx, src) - if err != nil { - return nil, ImageMetadata{}, err - } - defer release() - imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) - if err != nil { - return nil, ImageMetadata{}, err - } - return imgBytes, ImageMetadata{MimeType: mimeType}, nil -} - // GetGoImage retrieves image bytes from a camera source and decodes it into an image.Image type. func GetGoImage(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { resBytes, resMetadata, err := cam.Image(context.Background(), mimeType, nil) diff --git a/components/camera/videosourcewrappers.go b/components/camera/videosourcewrappers.go index 0741095e9cd..1d98a9c197a 100644 --- a/components/camera/videosourcewrappers.go +++ b/components/camera/videosourcewrappers.go @@ -197,6 +197,22 @@ func (vs *videoSource) Stream(ctx context.Context, errHandlers ...gostream.Error return vs.videoSource.Stream(ctx, errHandlers...) } +// ReadImageBytes wraps ReadImage given a mimetype to encode the image as bytes data, returning +// supplementary metadata for downstream processing. +// TODO(hexbabe): make function private or remove altogether once the usages are limited to this file. +func ReadImageBytes(ctx context.Context, src gostream.VideoSource, mimeType string) ([]byte, ImageMetadata, error) { + img, release, err := ReadImage(ctx, src) + if err != nil { + return nil, ImageMetadata{}, err + } + defer release() + imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) + if err != nil { + return nil, ImageMetadata{}, err + } + return imgBytes, ImageMetadata{MimeType: mimeType}, nil +} + func (vs *videoSource) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) { return ReadImageBytes(ctx, vs.videoSource, mimeType) } From 6ec004144938c215ad5e8c812a733ae6087b4523 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 13 Nov 2024 16:15:43 -0500 Subject: [PATCH 18/51] Rename GetGoImage -> ImageFromVideoSource --- components/camera/camera.go | 4 ++-- components/camera/camera_test.go | 4 ++-- components/camera/client.go | 2 +- components/camera/client_test.go | 8 ++++---- components/camera/fake/camera_test.go | 2 +- components/camera/fake/image_file_test.go | 2 +- robot/client/client_test.go | 2 +- robot/impl/local_robot_test.go | 3 ++- 8 files changed, 14 insertions(+), 13 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 82b0dd1dd19..72073e3a0ce 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -159,8 +159,8 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func return gostream.ReadImage(ctx, src) } -// GetGoImage retrieves image bytes from a camera source and decodes it into an image.Image type. -func GetGoImage(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { +// ImageFromVideoSource retrieves image bytes from a camera source and decodes it into an image.Image type. +func ImageFromVideoSource(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { resBytes, resMetadata, err := cam.Image(context.Background(), mimeType, nil) if err != nil { return nil, fmt.Errorf("could not get image bytes from camera: %w", err) diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index cd1bd2d8734..fcaec46e208 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -182,7 +182,7 @@ func TestCameraWithNoProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.GetGoImage(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) + img, err := camera.ImageFromVideoSource(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) @@ -229,7 +229,7 @@ func TestCameraWithProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.GetGoImage(context.Background(), rutils.MimeTypePNG, nil, cam2) + img, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypePNG, nil, cam2) test.That(t, err, test.ShouldBeNil) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/client.go b/components/camera/client.go index bc7eb248165..63cba52adbb 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -146,7 +146,7 @@ func (c *client) Stream( return } - img, err := GetGoImage(streamCtx, mimeTypeFromCtx, nil, c) + img, err := ImageFromVideoSource(streamCtx, mimeTypeFromCtx, nil, c) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 2bef77278db..011d64a42f0 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -175,7 +175,7 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - frame, err := camera.GetGoImage(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) + frame, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) @@ -222,7 +222,7 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frame, err := camera.GetGoImage(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) + frame, err := camera.ImageFromVideoSource(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) @@ -463,7 +463,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frame, err := camera.GetGoImage(ctx, rutils.MimeTypePNG, nil, camera1Client) + frame, err := camera.ImageFromVideoSource(ctx, rutils.MimeTypePNG, nil, camera1Client) test.That(t, err, test.ShouldBeNil) // Should always lazily decode test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) @@ -471,7 +471,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) ctx = context.Background() - frame, err = camera.GetGoImage(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) + frame, err = camera.ImageFromVideoSource(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) test.That(t, err, test.ShouldBeNil) test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) frameLazy = frame.(*rimage.LazyEncodedImage) diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index 505c7c1f7b1..c8c39058157 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -94,7 +94,7 @@ func TestRTPPassthrough(t *testing.T) { cam, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) - img, err := camera.GetGoImage(context.Background(), utils.MimeTypeRawRGBA, nil, cam) + img, err := camera.ImageFromVideoSource(context.Background(), utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index e427f87fe02..7c262a5643f 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -102,7 +102,7 @@ func TestColorOddResolution(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - strmImg, err := camera.GetGoImage(ctx, utils.MimeTypeRawRGBA, nil, cam) + strmImg, err := camera.ImageFromVideoSource(ctx, utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) expectedBounds := image.Rect(0, 0, img.Bounds().Dx()-1, img.Bounds().Dy()-1) diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 71b3b5571fd..06ae4692c5c 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -584,7 +584,7 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - frame, err := camera.GetGoImage(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) + frame, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 67bb79f051c..05469f59566 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -20,6 +20,7 @@ import ( "github.com/golang/geo/r3" "go.mongodb.org/mongo-driver/bson/primitive" "go.uber.org/zap" + // registers all components. commonpb "go.viam.com/api/common/v1" armpb "go.viam.com/api/component/arm/v1" @@ -93,7 +94,7 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - pic, err := camera.GetGoImage(context.Background(), rutils.MimeTypeJPEG, nil, c1) + pic, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeJPEG, nil, c1) test.That(t, err, test.ShouldBeNil) bounds := pic.Bounds() From ef1bd0e82103d1d4cf0723cc74ad674f11801e4d Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 13 Nov 2024 16:28:16 -0500 Subject: [PATCH 19/51] Make lint --- robot/impl/local_robot_test.go | 1 - 1 file changed, 1 deletion(-) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 05469f59566..a2e37c37132 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -20,7 +20,6 @@ import ( "github.com/golang/geo/r3" "go.mongodb.org/mongo-driver/bson/primitive" "go.uber.org/zap" - // registers all components. commonpb "go.viam.com/api/common/v1" armpb "go.viam.com/api/component/arm/v1" From d01159a3e3e74a0275b9a34caf11b3311f730c32 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 13 Nov 2024 17:53:48 -0500 Subject: [PATCH 20/51] Move mimetype unmarshaling outside of capture func --- components/camera/collector.go | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/components/camera/collector.go b/components/camera/collector.go index 78580727135..ba597e58a58 100644 --- a/components/camera/collector.go +++ b/components/camera/collector.go @@ -89,16 +89,17 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d } } + mimeStr := new(wrapperspb.StringValue) + if err := mimeType.UnmarshalTo(mimeStr); err != nil { + return nil, err + } + cFunc := data.CaptureFunc(func(ctx context.Context, _ map[string]*anypb.Any) (interface{}, error) { _, span := trace.StartSpan(ctx, "camera::data::collector::CaptureFunc::ReadImage") defer span.End() ctx = context.WithValue(ctx, data.FromDMContextKey{}, true) - mimeStr := new(wrapperspb.StringValue) - if err := mimeType.UnmarshalTo(mimeStr); err != nil { - return nil, err - } img, _, err := camera.Image(ctx, mimeStr.Value, nil) if err != nil { // A modular filter component can be created to filter the readings from a component. The error ErrNoCaptureToStore From 44611d53e5811a101582e3027bf0b24a0991b22b Mon Sep 17 00:00:00 2001 From: sean yu <55464069+hexbabe@users.noreply.github.com> Date: Wed, 13 Nov 2024 17:54:38 -0500 Subject: [PATCH 21/51] Update components/camera/client.go Co-authored-by: nicksanford --- components/camera/client.go | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/components/camera/client.go b/components/camera/client.go index 63cba52adbb..49c1a9efc77 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -197,8 +197,7 @@ func (c *client) Image(ctx context.Context, mimeType string, extra map[string]in resp.MimeType = mimeType } - resp.MimeType = utils.WithLazyMIMEType(resp.MimeType) - return resp.Image, ImageMetadata{MimeType: resp.MimeType}, nil + return resp.Image, ImageMetadata{MimeType: utils.WithLazyMIMEType(resp.MimeType)}, nil } func (c *client) Images(ctx context.Context) ([]NamedImage, resource.ResponseMetadata, error) { From 146345f0c1bbc3e8b62849dcefe95743066bcfaf Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 10:16:10 -0500 Subject: [PATCH 22/51] Add error for empty bytes responses in server & client --- components/camera/client.go | 3 +++ components/camera/server.go | 4 ++++ 2 files changed, 7 insertions(+) diff --git a/components/camera/client.go b/components/camera/client.go index 49c1a9efc77..0f6e25ba2f5 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -187,6 +187,9 @@ func (c *client) Image(ctx context.Context, mimeType string, extra map[string]in MimeType: expectedType, Extra: convertedExtra, }) + if len(resp.Image) == 0 { + return nil, ImageMetadata{}, errors.New("received empty bytes from client GetImage") + } if err != nil { return nil, ImageMetadata{}, err } diff --git a/components/camera/server.go b/components/camera/server.go index 6874803ff04..a38e68e9f5a 100644 --- a/components/camera/server.go +++ b/components/camera/server.go @@ -3,6 +3,7 @@ package camera import ( "bytes" "context" + "fmt" "image" "github.com/pkg/errors" @@ -74,6 +75,9 @@ func (s *serviceServer) GetImage( if err != nil { return nil, err } + if len(resBytes) == 0 { + return nil, fmt.Errorf("received empty bytes from Image method of %s", req.Name) + } actualMIME, _ := utils.CheckLazyMIMEType(resMetadata.MimeType) return &pb.GetImageResponse{MimeType: actualMIME, Image: resBytes}, nil } From c698e164502e727289a5c7849565c9c1c5d0a819 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 10:52:41 -0500 Subject: [PATCH 23/51] Add empty image bytes tests --- components/camera/camera.go | 7 +++++-- components/camera/client.go | 6 +++--- components/camera/client_test.go | 6 ++++++ components/camera/server_test.go | 14 +++++++++++++- 4 files changed, 27 insertions(+), 6 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 72073e3a0ce..9c706776c5c 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -161,11 +161,14 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func // ImageFromVideoSource retrieves image bytes from a camera source and decodes it into an image.Image type. func ImageFromVideoSource(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { - resBytes, resMetadata, err := cam.Image(context.Background(), mimeType, nil) + resBytes, resMetadata, err := cam.Image(ctx, mimeType, extra) if err != nil { return nil, fmt.Errorf("could not get image bytes from camera: %w", err) } - img, err := rimage.DecodeImage(context.Background(), resBytes, resMetadata.MimeType) + if len(resBytes) == 0 { + return nil, errors.New("received empty bytes from camera") + } + img, err := rimage.DecodeImage(ctx, resBytes, resMetadata.MimeType) if err != nil { return nil, fmt.Errorf("could not decode into image.Image: %w", err) } diff --git a/components/camera/client.go b/components/camera/client.go index 0f6e25ba2f5..86152b092e3 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -187,12 +187,12 @@ func (c *client) Image(ctx context.Context, mimeType string, extra map[string]in MimeType: expectedType, Extra: convertedExtra, }) - if len(resp.Image) == 0 { - return nil, ImageMetadata{}, errors.New("received empty bytes from client GetImage") - } if err != nil { return nil, ImageMetadata{}, err } + if len(resp.Image) == 0 { + return nil, ImageMetadata{}, errors.New("received empty bytes from client GetImage") + } if expectedType != "" && resp.MimeType != expectedType { c.logger.CDebugw(ctx, "got different MIME type than what was asked for", "sent", expectedType, "received", resp.MimeType) diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 011d64a42f0..26b4c930447 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -97,6 +97,9 @@ func TestClient(t *testing.T) { return images, resource.ResponseMetadata{CapturedAt: ts}, nil } injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + if val, ok := extra["empty"].(bool); ok && val { + return []byte{}, camera.ImageMetadata{}, nil + } resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) test.That(t, err, test.ShouldBeNil) return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil @@ -180,6 +183,9 @@ func TestClient(t *testing.T) { compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion + _, err = camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeRawRGBA, map[string]interface{}{"empty": true}, camera1Client) + test.That(t, err, test.ShouldNotBeNil) + test.That(t, err.Error(), test.ShouldContainSubstring, "received empty bytes from Image method") pcB, err := camera1Client.NextPointCloud(context.Background()) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/server_test.go b/components/camera/server_test.go index 9e932c8b969..e862cc18828 100644 --- a/components/camera/server_test.go +++ b/components/camera/server_test.go @@ -108,6 +108,7 @@ func TestServer(t *testing.T) { return projA, nil } wooMIME := "image/woohoo" + emptyMIME := "image/empty" injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { if mimeType == "" { mimeType = utils.MimeTypeRawRGBA @@ -122,8 +123,10 @@ func TestServer(t *testing.T) { respImg = imgPng case utils.MimeTypeJPEG: respImg = imgJpeg - case "image/woohoo": + case wooMIME: respImg = rimage.NewLazyEncodedImage([]byte{1, 2, 3}, mimeType) + case emptyMIME: + return []byte{}, camera.ImageMetadata{}, nil default: return nil, camera.ImageMetadata{}, errInvalidMimeType } @@ -261,6 +264,15 @@ func TestServer(t *testing.T) { test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) }) + t.Run("GetImage response was empty", func(t *testing.T) { + _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ + Name: testCameraName, + MimeType: emptyMIME, + }) + test.That(t, err, test.ShouldNotBeNil) + test.That(t, err.Error(), test.ShouldContainSubstring, "received empty bytes from Image method") + }) + t.Run("GetImage with lazy", func(t *testing.T) { // we know its lazy if it's a mime we can't actually handle internally resp, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ From 9da582f04f43a33d398fb487f3f5a50d89363b7c Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 12:23:54 -0500 Subject: [PATCH 24/51] Fix random things that I am doing wrong --- components/camera/camera.go | 2 +- components/camera/fake/image_file_test.go | 6 ++-- components/camera/replaypcd/replaypcd_test.go | 5 +++ components/camera/server_test.go | 2 +- .../datamanager/builtin/builtin_sync_test.go | 32 +++++++------------ 5 files changed, 22 insertions(+), 25 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 9c706776c5c..2c946f4e2fb 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -96,7 +96,7 @@ type Camera interface { // Or try to directly decode into an image.Image: // // myCamera, err := camera.FromRobot(machine, "my_camera") -// img, err = camera.GetGoImage(context.Background(), utils.MimeTypeJPEG, nil, myCamera) +// img, err = camera.ImageFromVideoSource(context.Background(), utils.MimeTypeJPEG, nil, myCamera) // // Images example: // diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index 7c262a5643f..cd089d91c31 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -85,13 +85,13 @@ func TestColorOddResolution(t *testing.T) { imgFile, err := os.Create(imgFilePath) test.That(t, err, test.ShouldBeNil) - img := image.NewNRGBA(image.Rect(0, 0, 3, 3)) + img := image.NewRGBA(image.Rect(0, 0, 3, 3)) for x := 0; x < img.Bounds().Dx(); x++ { for y := 0; y < img.Bounds().Dy(); y++ { img.Set(x, y, color.White) } } - err = jpeg.Encode(imgFile, img, &jpeg.Options{Quality: 75}) + err = jpeg.Encode(imgFile, img, nil) test.That(t, err, test.ShouldBeNil) err = imgFile.Close() test.That(t, err, test.ShouldBeNil) @@ -109,7 +109,7 @@ func TestColorOddResolution(t *testing.T) { test.That(t, strmImg.Bounds(), test.ShouldResemble, expectedBounds) val, _, err := rimage.CompareImages(strmImg, img.SubImage(expectedBounds)) test.That(t, err, test.ShouldBeNil) - test.That(t, val, test.ShouldBeLessThanOrEqualTo, 0) + test.That(t, val, test.ShouldEqual, 0) err = cam.Close(ctx) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/replaypcd/replaypcd_test.go b/components/camera/replaypcd/replaypcd_test.go index 39a60203010..90b397edc21 100644 --- a/components/camera/replaypcd/replaypcd_test.go +++ b/components/camera/replaypcd/replaypcd_test.go @@ -660,6 +660,11 @@ func TestReplayPCDUnimplementedFunctions(t *testing.T) { replayCamera, _, serverClose, err := createNewReplayPCDCamera(ctx, t, replayCamCfg, true) test.That(t, err, test.ShouldBeNil) + t.Run("Stream", func(t *testing.T) { + _, err := replayCamera.Stream(ctx, nil) + test.That(t, err.Error(), test.ShouldEqual, "Stream is unimplemented") + }) + err = replayCamera.Close(ctx) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/server_test.go b/components/camera/server_test.go index e862cc18828..55832a12c97 100644 --- a/components/camera/server_test.go +++ b/components/camera/server_test.go @@ -264,7 +264,7 @@ func TestServer(t *testing.T) { test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) }) - t.Run("GetImage response was empty", func(t *testing.T) { + t.Run("GetImage response image bytes empty", func(t *testing.T) { _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ Name: testCameraName, MimeType: emptyMIME, diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index b212c50ab4e..be4ae485b84 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -159,11 +159,7 @@ func TestSyncEnabled(t *testing.T) { mimeType string, extra map[string]interface{}, ) ([]byte, camera.ImageMetadata, error) { - outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return newImageBytesResp(ctx, imgPng, mimeType) }, }, }) @@ -366,11 +362,7 @@ func TestDataCaptureUploadIntegration(t *testing.T) { mimeType string, extra map[string]interface{}, ) ([]byte, camera.ImageMetadata, error) { - outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return newImageBytesResp(ctx, imgPng, mimeType) }, }, }) @@ -773,11 +765,7 @@ func TestStreamingDCUpload(t *testing.T) { mimeType string, extra map[string]interface{}, ) ([]byte, camera.ImageMetadata, error) { - outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return newImageBytesResp(ctx, imgPng, mimeType) }, }, }) @@ -1018,11 +1006,7 @@ func TestSyncConfigUpdateBehavior(t *testing.T) { mimeType string, extra map[string]interface{}, ) ([]byte, camera.ImageMetadata, error) { - outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return newImageBytesResp(ctx, imgPng, mimeType) }, }, }) @@ -1176,6 +1160,14 @@ func populateFileContents(fileContents []byte) []byte { return fileContents } +func newImageBytesResp(ctx context.Context, img image.Image, mimeType string) ([]byte, camera.ImageMetadata, error) { + outBytes, err := rimage.EncodeImage(ctx, img, mimeType) + if err != nil { + return nil, camera.ImageMetadata{}, err + } + return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil +} + func newImgPng(t *testing.T) image.Image { img := image.NewNRGBA(image.Rect(0, 0, 4, 4)) var imgBuf bytes.Buffer From 1b5110912ba3d04bf06fd7251f00aba770b7f95c Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 13:33:32 -0500 Subject: [PATCH 25/51] Revert --- services/datamanager/builtin/builtin_sync_test.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index be4ae485b84..5c2061b8221 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -38,7 +38,7 @@ const ( waitTime = syncInterval * 4 ) -// TODO DATA-849: Add a test that validates that sync interval is accurately respected. +// TODO DATA-849: Add a test that validates that the sync interval is accurately respected. func TestSyncEnabled(t *testing.T) { tests := []struct { name string From eaf28d771ff99824dc3057deeb32a25c53d9d2aa Mon Sep 17 00:00:00 2001 From: Dan Gottlieb Date: Wed, 6 Nov 2024 14:32:47 -0500 Subject: [PATCH 26/51] RSDK-9218: Change all of the artifacts to v4. (#4535) --- .github/workflows/appimage.yml | 4 ++-- .github/workflows/code-coverage-comment.yml | 4 ++-- .github/workflows/motion-benchmarks-comment.yml | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/appimage.yml b/.github/workflows/appimage.yml index 9bba1da89d0..a4b3fb48e89 100644 --- a/.github/workflows/appimage.yml +++ b/.github/workflows/appimage.yml @@ -140,7 +140,7 @@ jobs: - uses: actions/checkout@v4 with: ref: ${{ github.event == 'pull_request_target' && github.event.pull_request.head.sha || github.ref }} - - uses: actions/download-artifact@v3 + - uses: actions/download-artifact@v4 with: name: appimage-static-32bit path: bin/ @@ -240,7 +240,7 @@ jobs: - name: Set up Cloud SDK uses: google-github-actions/setup-gcloud@v1 - - uses: actions/download-artifact@v3 + - uses: actions/download-artifact@v4 with: name: appimage-armhf path: etc/packaging/appimages/deploy diff --git a/.github/workflows/code-coverage-comment.yml b/.github/workflows/code-coverage-comment.yml index 3753bcd1143..be0f95b73b2 100644 --- a/.github/workflows/code-coverage-comment.yml +++ b/.github/workflows/code-coverage-comment.yml @@ -12,9 +12,9 @@ jobs: if: ${{ github.event.workflow_run.event == 'pull_request_target' && github.event.workflow_run.conclusion == 'success' }} steps: - name: Download Code Coverage - uses: dawidd6/action-download-artifact@v2 + uses: actions/download-artifact@v4 with: - run_id: ${{ github.event.workflow_run.id }} + run-id: ${{ github.event.workflow_run.id }} name: pr-code-coverage - name: Restore Environment diff --git a/.github/workflows/motion-benchmarks-comment.yml b/.github/workflows/motion-benchmarks-comment.yml index 1d725530566..fc10b0fb9a3 100644 --- a/.github/workflows/motion-benchmarks-comment.yml +++ b/.github/workflows/motion-benchmarks-comment.yml @@ -12,9 +12,9 @@ jobs: if: ${{ github.event.workflow_run.event == 'pull_request_target' && github.event.workflow_run.conclusion == 'success' }} steps: - name: Download Motion Benchmarks - uses: dawidd6/action-download-artifact@v2 + uses: actions/download-artifact@v4 with: - run_id: ${{ github.event.workflow_run.id }} + run-id: ${{ github.event.workflow_run.id }} name: pr-motion-benchmark - name: Restore Environment From 4fe7e361a94a719c74a05680c770898fae307c24 Mon Sep 17 00:00:00 2001 From: Dan Gottlieb Date: Wed, 6 Nov 2024 14:50:15 -0500 Subject: [PATCH 27/51] RSDK-8359: Update smarty to avoid unnecessary data races. (#4534) --- go.mod | 4 +- go.sum | 150 ++------------------------------------------------------- 2 files changed, 6 insertions(+), 148 deletions(-) diff --git a/go.mod b/go.mod index bc82ad14c81..0258bd23bf7 100644 --- a/go.mod +++ b/go.mod @@ -83,7 +83,7 @@ require ( go.uber.org/multierr v1.11.0 go.uber.org/zap v1.27.0 go.viam.com/api v0.1.357 - go.viam.com/test v1.1.1-0.20220913152726-5da9916c08a2 + go.viam.com/test v1.2.3 go.viam.com/utils v0.1.112 goji.io v2.0.2+incompatible golang.org/x/image v0.19.0 @@ -188,6 +188,7 @@ require ( github.com/decred/dcrd/dcrec/secp256k1/v4 v4.2.0 // indirect github.com/denis-tingaikin/go-header v0.5.0 // indirect github.com/desertbit/timer v0.0.0-20180107155436-c41aec40b27f // indirect + github.com/dgottlieb/smarty-assertions v1.2.5 // indirect github.com/dnephin/pflag v1.0.7 // indirect github.com/docker/cli v24.0.2+incompatible // indirect github.com/docker/distribution v2.8.2+incompatible // indirect @@ -364,7 +365,6 @@ require ( github.com/sirupsen/logrus v1.9.3 // indirect github.com/sivchari/containedctx v1.0.3 // indirect github.com/sivchari/tenv v1.10.0 // indirect - github.com/smartystreets/assertions v1.13.0 // indirect github.com/sonatard/noctx v0.0.2 // indirect github.com/sourcegraph/go-diff v0.7.0 // indirect github.com/spf13/afero v1.11.0 // indirect diff --git a/go.sum b/go.sum index 9725aeda15f..21bb07927fa 100644 --- a/go.sum +++ b/go.sum @@ -3,7 +3,6 @@ 4d63.com/gochecknoglobals v0.0.0-20201008074935-acfc0b28355a/go.mod h1:wfdC5ZjKSPr7CybKEcgJhUOgeAQW1+7WcyK8OvUilfo= 4d63.com/gochecknoglobals v0.2.1 h1:1eiorGsgHOFOuoOiJDy2psSrQbRdIHrlge0IJIkUgDc= 4d63.com/gochecknoglobals v0.2.1/go.mod h1:KRE8wtJB3CXCsb1xy421JfTHIIbmT3U5ruxw2Qu8fSU= -bitbucket.org/creachadair/shell v0.0.6/go.mod h1:8Qqi/cYk7vPnsOePHroKXDJYmb5x7ENhtiFtfZq8K+M= cel.dev/expr v0.15.0 h1:O1jzfJCQBfL5BFoYktaxwIhuttaQPsVWerH9/EEKx0w= cel.dev/expr v0.15.0/go.mod h1:TRSuuV7DlVCE/uwv5QbAiW/v8l5O8C4eEPHeu7gf7Sg= cloud.google.com/go v0.26.0/go.mod h1:aQUYkXzVsufM+DwF1aE+0xfcU+56JwCaLick0ClmMTw= @@ -19,7 +18,6 @@ cloud.google.com/go v0.53.0/go.mod h1:fp/UouUEsRkN6ryDKNW/Upv/JBKnv6WDthjR6+vze6 cloud.google.com/go v0.54.0/go.mod h1:1rq2OEkV3YMf6n/9ZvGWI3GWw0VoqH/1x2nd8Is/bPc= cloud.google.com/go v0.56.0/go.mod h1:jr7tqZxxKOVYizybht9+26Z/gUq7tiRzu+ACVAMbKVk= cloud.google.com/go v0.57.0/go.mod h1:oXiQ6Rzq3RAkkY7N6t3TcE6jE+CIBBbA36lwQ1JyzZs= -cloud.google.com/go v0.60.0/go.mod h1:yw2G51M9IfRboUH61Us8GqCeF1PzPblB823Mn2q2eAU= cloud.google.com/go v0.62.0/go.mod h1:jmCYTdRCQuc1PHIIJ/maLInMho30T/Y0M4hTdTShOYc= cloud.google.com/go v0.65.0/go.mod h1:O5N8zS7uWy9vkA9vayVHs65eM1ubvY4h553ofrNHObY= cloud.google.com/go v0.115.1 h1:Jo0SM9cQnSkYfp44+v+NQXHpcHqlnRJk2qxh6yvxxxQ= @@ -51,8 +49,6 @@ cloud.google.com/go/pubsub v1.0.1/go.mod h1:R0Gpsv3s54REJCy4fxDixWD93lHJMoZTyQ2k cloud.google.com/go/pubsub v1.1.0/go.mod h1:EwwdRX2sKPjnvnqCa270oGRyludottCI76h+R3AArQw= cloud.google.com/go/pubsub v1.2.0/go.mod h1:jhfEVHT8odbXTkndysNHCcx0awwzvfOlguIAii9o8iA= cloud.google.com/go/pubsub v1.3.1/go.mod h1:i+ucay31+CNRpDW4Lu78I4xXG+O1r/MAHgjpRVR+TSU= -cloud.google.com/go/pubsub v1.5.0/go.mod h1:ZEwJccE3z93Z2HWvstpri00jOg7oO4UZDtKhwDwqF0w= -cloud.google.com/go/spanner v1.7.0/go.mod h1:sd3K2gZ9Fd0vMPLXzeCrF6fq4i63Q7aTLW/lBIfBkIk= cloud.google.com/go/storage v1.0.0/go.mod h1:IhtSnM/ZTZV8YYJWCY8RULGVqBDmpoyjwiyrjsg+URw= cloud.google.com/go/storage v1.5.0/go.mod h1:tpKbwo567HUNpVclU5sGELwQWBDZ8gh0ZeosJ0Rtdos= cloud.google.com/go/storage v1.6.0/go.mod h1:N7U0C8pVQ/+NIKOBQyamJIeKQKkZ+mxpohlUTyfDhBk= @@ -95,15 +91,12 @@ github.com/GaijinEntertainment/go-exhaustruct/v3 v3.3.0/go.mod h1:ONJg5sxcbsdQQ4 github.com/Knetic/govaluate v3.0.1-0.20171022003610-9aa49832a739+incompatible/go.mod h1:r7JcOSlj0wfOMncg0iLm8Leh48TZaKVeNIfJntJ2wa0= github.com/MakeNowJust/heredoc v1.0.0 h1:cXCdzVdstXyiTqTvfqk9SDHpKNjxuom+DOlyEeQ4pzQ= github.com/MakeNowJust/heredoc v1.0.0/go.mod h1:mG5amYoWBHf8vpLOuehzbGGw0EHxpZZ6lCpQ4fNJ8LE= -github.com/Masterminds/goutils v1.1.0/go.mod h1:8cTjp+g8YejhMuvIA5y2vz3BpJxksy863GQaJW2MFNU= github.com/Masterminds/goutils v1.1.1 h1:5nUrii3FMTL5diU80unEVvNevw1nH4+ZV4DSLVJLSYI= github.com/Masterminds/goutils v1.1.1/go.mod h1:8cTjp+g8YejhMuvIA5y2vz3BpJxksy863GQaJW2MFNU= -github.com/Masterminds/semver v1.4.2/go.mod h1:MB6lktGJrhw8PrUyiEoblNEGEQ+RzHPF078ddwwvV3Y= github.com/Masterminds/semver v1.5.0 h1:H65muMkzWKEuNDnfl9d70GUjFniHKHRbFPGBuZ3QEww= github.com/Masterminds/semver v1.5.0/go.mod h1:MB6lktGJrhw8PrUyiEoblNEGEQ+RzHPF078ddwwvV3Y= github.com/Masterminds/semver/v3 v3.3.0 h1:B8LGeaivUe71a5qox1ICM/JLl0NqZSW5CHyL+hmvYS0= github.com/Masterminds/semver/v3 v3.3.0/go.mod h1:4V+yj/TJE1HU9XfppCwVMZq3I84lprf4nC11bSS5beM= -github.com/Masterminds/sprig v2.15.0+incompatible/go.mod h1:y6hNFY5UBTIWBxnzTeuNhlNS5hqE0NB0E6fgfo2Br3o= github.com/Masterminds/sprig v2.22.0+incompatible h1:z4yfnGrZ7netVz+0EDJ0Wi+5VZCSYp4Z0m2dk6cEM60= github.com/Masterminds/sprig v2.22.0+incompatible/go.mod h1:y6hNFY5UBTIWBxnzTeuNhlNS5hqE0NB0E6fgfo2Br3o= github.com/Microsoft/go-winio v0.6.1 h1:9/kr64B9VUZrLm5YYwbGtUJnMgqWVOdUAXu6Migciow= @@ -145,15 +138,12 @@ github.com/alexkohler/prealloc v1.0.0/go.mod h1:VetnK3dIgFBBKmg0YnD9F9x6Icjd+9cv github.com/alingse/asasalint v0.0.11 h1:SFwnQXJ49Kx/1GghOFz1XGqHYKp21Kq1nHad/0WQRnw= github.com/alingse/asasalint v0.0.11/go.mod h1:nCaoMhw7a9kSJObvQyVzNTPBDbNpdocqrSP7t/cW5+I= github.com/andybalholm/brotli v1.0.0/go.mod h1:loMXtMfwqflxFJPmdbJO0a3KNoPuLBgiu3qAvBg8x/Y= -github.com/antihax/optional v0.0.0-20180407024304-ca021399b1a6/go.mod h1:V8iCPQYkqmusNa815XgQio277wI47sdRh1dUOLdyC6Q= github.com/antihax/optional v1.0.0/go.mod h1:uupD/76wgC+ih3iEmQUL+0Ugr19nfwCT1kdvxnR2qWY= -github.com/aokoli/goutils v1.0.1/go.mod h1:SijmP0QR8LtwsmDs8Yii5Z/S4trXFGFC2oO5g9DP+DQ= github.com/apache/arrow/go/arrow v0.0.0-20201229220542-30ce2eb5d4dc h1:zvQ6w7KwtQWgMQiewOF9tFtundRMVZFSAksNV6ogzuY= github.com/apache/arrow/go/arrow v0.0.0-20201229220542-30ce2eb5d4dc/go.mod h1:c9sxoIT3YgLxH4UhLOCKaBlEojuMhVYpk4Ntv3opUTQ= github.com/apache/thrift v0.12.0/go.mod h1:cp2SuWMxlEZw2r+iP2GNCdIi4C1qmUzdZFSVb+bacwQ= github.com/apache/thrift v0.13.0/go.mod h1:cp2SuWMxlEZw2r+iP2GNCdIi4C1qmUzdZFSVb+bacwQ= github.com/armon/circbuf v0.0.0-20150827004946-bbbad097214e/go.mod h1:3U/XgcO3hCbHZ8TKRvWD2dDTCfh9M9ya+I9JpbB7O8o= -github.com/armon/consul-api v0.0.0-20180202201655-eb2c6b5be1b6/go.mod h1:grANhF5doyWs3UAsr3K4I6qtAmlQcZDesFNEHPZAzj8= github.com/armon/go-metrics v0.0.0-20180917152333-f0300d1749da/go.mod h1:Q73ZrmVTwzkszR9V5SSuryQ31EELlFMUz1kKyl939pY= github.com/armon/go-radix v0.0.0-20180808171621-7fddfc383310/go.mod h1:ufUuZ+zHj4x4TnLV4JWEpy2hxWSpsRywHrMgIH9cCH8= github.com/aryann/difflib v0.0.0-20170710044230-e206f873d14a/go.mod h1:DAHtR1m6lCRdSC2Tm3DSWRPvIPr6xNKyeHdqDQSQT+A= @@ -161,16 +151,13 @@ github.com/ashanbrown/forbidigo v1.1.0/go.mod h1:vVW7PEdqEFqapJe95xHkTfB1+XvZXBF github.com/ashanbrown/forbidigo v1.6.0 h1:D3aewfM37Yb3pxHujIPSpTf6oQk9sc9WZi8gerOIVIY= github.com/ashanbrown/forbidigo v1.6.0/go.mod h1:Y8j9jy9ZYAEHXdu723cUlraTqbzjKF1MUyfOKL+AjcU= github.com/ashanbrown/makezero v0.0.0-20201205152432-7b7cdbb3025a/go.mod h1:oG9Dnez7/ESBqc4EdrdNlryeo7d0KcW1ftXHm7nU/UU= -github.com/ashanbrown/makezero v0.0.0-20210308000810-4155955488a0/go.mod h1:oG9Dnez7/ESBqc4EdrdNlryeo7d0KcW1ftXHm7nU/UU= github.com/ashanbrown/makezero v1.1.1 h1:iCQ87C0V0vSyO+M9E/FZYbu65auqH0lnsOkf5FcB28s= github.com/ashanbrown/makezero v1.1.1/go.mod h1:i1bJLCRSCHOcOa9Y6MyF2FTfMZMFdHvxKHxgO5Z1axI= github.com/atotto/clipboard v0.1.4 h1:EH0zSVneZPSuFR11BlR9YppQTVDbh5+16AmcJi4g1z4= github.com/atotto/clipboard v0.1.4/go.mod h1:ZY9tmq7sm5xIbd9bOK4onWV4S6X0u6GY7Vn0Yu86PYI= github.com/aws/aws-lambda-go v1.13.3/go.mod h1:4UKl9IzQMoD+QF79YdCuzCwp8VbmG4VAQwij/eHl5CU= github.com/aws/aws-sdk-go v1.23.20/go.mod h1:KmX6BPdI08NWTb3/sm4ZGu5ShLoqVDhKgpiN924inxo= -github.com/aws/aws-sdk-go v1.25.37/go.mod h1:KmX6BPdI08NWTb3/sm4ZGu5ShLoqVDhKgpiN924inxo= github.com/aws/aws-sdk-go v1.27.0/go.mod h1:KmX6BPdI08NWTb3/sm4ZGu5ShLoqVDhKgpiN924inxo= -github.com/aws/aws-sdk-go v1.36.30/go.mod h1:hcU610XS61/+aQV88ixoOzUoG7v3b31pl2zKMmprdro= github.com/aws/aws-sdk-go v1.38.20 h1:QbzNx/tdfATbdKfubBpkt84OM6oBkxQZRw6+bW2GyeA= github.com/aws/aws-sdk-go v1.38.20/go.mod h1:hcU610XS61/+aQV88ixoOzUoG7v3b31pl2zKMmprdro= github.com/aws/aws-sdk-go-v2 v0.18.0/go.mod h1:JWVYvqSMppoMJC0x5wdwiImzgXTI9FuZwxzkQq9wy+g= @@ -296,19 +283,15 @@ github.com/codahale/hdrhistogram v0.0.0-20161010025455-3a0bb77429bd/go.mod h1:sE github.com/containerd/stargz-snapshotter/estargz v0.14.3 h1:OqlDCK3ZVUO6C3B/5FSkDwbkEETK84kQgEeFwDC+62k= github.com/containerd/stargz-snapshotter/estargz v0.14.3/go.mod h1:KY//uOCIkSuNAHhJogcZtrNHdKrA99/FCCRjE3HD36o= github.com/coreos/bbolt v1.3.2/go.mod h1:iRUV2dpdMOn7Bo10OQBFzIJO9kkE559Wcmn+qkEiiKk= -github.com/coreos/etcd v3.3.10+incompatible/go.mod h1:uF7uidLiAD3TWHmW31ZFd/JWoc32PjwdhPthX9715RE= github.com/coreos/etcd v3.3.13+incompatible/go.mod h1:uF7uidLiAD3TWHmW31ZFd/JWoc32PjwdhPthX9715RE= -github.com/coreos/go-etcd v2.0.0+incompatible/go.mod h1:Jez6KQU2B/sWsbdaef3ED8NzMklzPG4d5KIOhIy30Tk= github.com/coreos/go-semver v0.2.0/go.mod h1:nnelYz7RCh+5ahJtPPxZlU+153eP4D4r3EedlOD2RNk= github.com/coreos/go-semver v0.3.0/go.mod h1:nnelYz7RCh+5ahJtPPxZlU+153eP4D4r3EedlOD2RNk= github.com/coreos/go-systemd v0.0.0-20180511133405-39ca1b05acc7/go.mod h1:F5haX7vjVVG0kc13fIWeqUViNPyEJxv/OmvnBo0Yme4= github.com/coreos/go-systemd v0.0.0-20190321100706-95778dfbb74e/go.mod h1:F5haX7vjVVG0kc13fIWeqUViNPyEJxv/OmvnBo0Yme4= -github.com/coreos/go-systemd v0.0.0-20190620071333-e64a0ec8b42a/go.mod h1:F5haX7vjVVG0kc13fIWeqUViNPyEJxv/OmvnBo0Yme4= github.com/coreos/pkg v0.0.0-20160727233714-3ac0863d7acf/go.mod h1:E3G3o1h8I7cfcXa63jLwjI0eiQQMgzzUDFVpN/nH/eA= github.com/coreos/pkg v0.0.0-20180928190104-399ea9e2e55f/go.mod h1:E3G3o1h8I7cfcXa63jLwjI0eiQQMgzzUDFVpN/nH/eA= github.com/corona10/goimagehash v1.0.2 h1:pUfB0LnsJASMPGEZLj7tGY251vF+qLGqOgEP4rUs6kA= github.com/corona10/goimagehash v1.0.2/go.mod h1:/l9umBhvcHQXVtQO1V6Gp1yD20STawkhRnnX0D1bvVI= -github.com/cpuguy83/go-md2man v1.0.10/go.mod h1:SmD6nW6nTyfqj6ABTjUi3V3JVMnlJmwcJI5acqYI6dE= github.com/cpuguy83/go-md2man/v2 v2.0.0-20190314233015-f79a8a8ca69d/go.mod h1:maD7wRr/U5Z6m/iR4s+kqSMx2CaBsrgA7czyZG/E6dU= github.com/cpuguy83/go-md2man/v2 v2.0.0/go.mod h1:maD7wRr/U5Z6m/iR4s+kqSMx2CaBsrgA7czyZG/E6dU= github.com/cpuguy83/go-md2man/v2 v2.0.2/go.mod h1:tgQtvFlXSQOSOSIRvRPT7W67SCa46tRHOmNcaadrF8o= @@ -327,7 +310,6 @@ github.com/d2r2/go-logger v0.0.0-20210606094344-60e9d1233e22/go.mod h1:eSx+YfcVy github.com/daixiang0/gci v0.2.8/go.mod h1:+4dZ7TISfSmqfAGv59ePaHfNzgGtIkHAhhdKggP1JAc= github.com/daixiang0/gci v0.13.5 h1:kThgmH1yBmZSBCh1EJVxQ7JsHpm5Oms0AMed/0LaH4c= github.com/daixiang0/gci v0.13.5/go.mod h1:12etP2OniiIdP4q+kjUGrC/rUagga7ODbqsom5Eo5Yk= -github.com/davecgh/go-spew v0.0.0-20161028175848-04cdfd42973b/go.mod h1:J7Y8YcW2NihsgmVo/mv3lAwl/skON4iLHjSsI+c5H38= github.com/davecgh/go-spew v1.1.0/go.mod h1:J7Y8YcW2NihsgmVo/mv3lAwl/skON4iLHjSsI+c5H38= github.com/davecgh/go-spew v1.1.1 h1:vj9j/u1bqnvCEfJOwUhtlOARqs3+rkHYY13jYWTU97c= github.com/davecgh/go-spew v1.1.1/go.mod h1:J7Y8YcW2NihsgmVo/mv3lAwl/skON4iLHjSsI+c5H38= @@ -341,6 +323,8 @@ github.com/denis-tingaikin/go-header v0.5.0/go.mod h1:mMenU5bWrok6Wl2UsZjy+1okeg github.com/denis-tingajkin/go-header v0.4.2/go.mod h1:eLRHAVXzE5atsKAnNRDB90WHCFFnBUn4RN0nRcs1LJA= github.com/desertbit/timer v0.0.0-20180107155436-c41aec40b27f h1:U5y3Y5UE0w7amNe7Z5G/twsBW0KEalRQXZzf8ufSh9I= github.com/desertbit/timer v0.0.0-20180107155436-c41aec40b27f/go.mod h1:xH/i4TFMt8koVQZ6WFms69WAsDWr2XsYL3Hkl7jkoLE= +github.com/dgottlieb/smarty-assertions v1.2.5 h1:CQQeh5VM6AVRxJmKlnqusMAqVSm9a3ng60gFD3l4QFU= +github.com/dgottlieb/smarty-assertions v1.2.5/go.mod h1:x1wpV/RTxYWtN+vgrcRuCF4hjUmonK5NR59ZzQSym2k= github.com/dgrijalva/jwt-go v3.2.0+incompatible/go.mod h1:E3ru+11k8xSBh+hMPgOLZmtrrCbhqsmaPHjLKYnJCaQ= github.com/dgryski/go-sip13 v0.0.0-20181026042036-e10d5fee7954/go.mod h1:vAd38F8PWV+bWy6jNmig1y/TA+kYO4g3RSRF0IAv0no= github.com/disintegration/imaging v1.6.2 h1:w1LecBlG2Lnp8B3jk5zSuNqd7b4DXhcjwek1ei82L+c= @@ -360,7 +344,6 @@ github.com/docker/go-connections v0.4.0/go.mod h1:Gbd7IOopHjR8Iph03tsViu4nIes5Xh github.com/docker/go-units v0.5.0 h1:69rxXcBk27SvSaaxTtLh/8llcHD8vYHT7WSdRZ/jvr4= github.com/docker/go-units v0.5.0/go.mod h1:fgPhTUdO+D/Jk86RDLlptpiXQzgHJF7gydDDbaIK4Dk= github.com/dustin/go-humanize v0.0.0-20171111073723-bb3d318650d4/go.mod h1:HtrtbFcZ19U5GC7JDqmcUSB87Iq5E25KnS6fMYU6eOk= -github.com/dustin/go-humanize v1.0.0/go.mod h1:HtrtbFcZ19U5GC7JDqmcUSB87Iq5E25KnS6fMYU6eOk= github.com/dustin/go-humanize v1.0.1 h1:GzkhY7T5VNhEkwH0PVJgjz+fX1rhBrR7pRT3mDkpeCY= github.com/dustin/go-humanize v1.0.1/go.mod h1:Mu1zIs6XwVuF/gI1OepvI0qD18qycQx+mFykh5fBlto= github.com/eapache/go-resiliency v1.1.0/go.mod h1:kFI+JgMyC7bLPUVY133qvEBtVayf5mFgVsvEsIPBvNs= @@ -387,7 +370,6 @@ github.com/envoyproxy/go-control-plane v0.9.9-0.20201210154907-fd9021fe5dad/go.m github.com/envoyproxy/go-control-plane v0.9.10-0.20210907150352-cf90f659a021/go.mod h1:AFq3mo9L8Lqqiid3OhADV3RfLJnjiw63cSpi+fDTRC0= github.com/envoyproxy/go-control-plane v0.12.1-0.20240621013728-1eb8caab5155 h1:IgJPqnrlY2Mr4pYB6oaMKvFvwJ9H+X6CCY5x1vCTcpc= github.com/envoyproxy/go-control-plane v0.12.1-0.20240621013728-1eb8caab5155/go.mod h1:5Wkq+JduFtdAXihLmeTJf+tRYIT4KBc2vPXDhwVo1pA= -github.com/envoyproxy/protoc-gen-validate v0.0.14/go.mod h1:iSmxcyjqTsJpI2R4NaDN7+kN2VEUnK/pcBlmesArF7c= github.com/envoyproxy/protoc-gen-validate v0.1.0/go.mod h1:iSmxcyjqTsJpI2R4NaDN7+kN2VEUnK/pcBlmesArF7c= github.com/envoyproxy/protoc-gen-validate v1.0.4 h1:gVPz/FMfvh57HdSJQyvBtF00j8JU4zdyUgIUNhlgg0A= github.com/envoyproxy/protoc-gen-validate v1.0.4/go.mod h1:qys6tmnRsYrQqIhm2bvKZH4Blx/1gTIZ2UKVY1M+Yew= @@ -396,7 +378,6 @@ github.com/erikgeiser/coninput v0.0.0-20211004153227-1c3628e74d0f/go.mod h1:vw97 github.com/erikstmartin/go-testdb v0.0.0-20160219214506-8d10e4a1bae5 h1:Yzb9+7DPaBjB8zlTR87/ElzFsnQfuHnVUVqpZZIcV5Y= github.com/erikstmartin/go-testdb v0.0.0-20160219214506-8d10e4a1bae5/go.mod h1:a2zkGnVExMxdzMo3M0Hi/3sEU+cWnZpSni0O6/Yb/P0= github.com/esimonov/ifshort v1.0.1/go.mod h1:yZqNJUrNn20K8Q9n2CrjTKYyVEmX209Hgu+M1LBpeZE= -github.com/esimonov/ifshort v1.0.2/go.mod h1:yZqNJUrNn20K8Q9n2CrjTKYyVEmX209Hgu+M1LBpeZE= github.com/ettle/strcase v0.2.0 h1:fGNiVF21fHXpX1niBgk0aROov1LagYsOwV/xqKDKR/Q= github.com/ettle/strcase v0.2.0/go.mod h1:DajmHElDSaX76ITe3/VHVyMin4LWSJN5Z909Wp+ED1A= github.com/fatih/addlint v0.0.0-20190906181921-76b21bd409a2/go.mod h1:jDmgAsni5lF2hjg3Eozc5y+Uh9hE26oBfZ1fCLSet0U= @@ -427,7 +408,6 @@ github.com/fsnotify/fsnotify v1.4.9/go.mod h1:znqG4EE+3YCdAaPaxE2ZRY/06pZUdp0tY4 github.com/fsnotify/fsnotify v1.5.4/go.mod h1:OVB6XrOHzAwXMpEM7uPOzcehqUV2UqJxmVXmkdnm1bU= github.com/fsnotify/fsnotify v1.6.0 h1:n+5WquG0fcWoWp6xPWfHdbskMCQaFnG6PfBrh1Ky4HY= github.com/fsnotify/fsnotify v1.6.0/go.mod h1:sl3t1tCWJFWoRz9R8WJCbQihKKwmorjAbSClcnxKAGw= -github.com/fullstorydev/grpcurl v1.6.0/go.mod h1:ZQ+ayqbKMJNhzLmbpCiurTVlaK2M/3nqZCxaQ2Ze/sM= github.com/fullstorydev/grpcurl v1.8.6 h1:WylAwnPauJIofYSHqqMTC1eEfUIzqzevXyogBxnQquo= github.com/fullstorydev/grpcurl v1.8.6/go.mod h1:WhP7fRQdhxz2TkL97u+TCb505sxfH78W1usyoB3tepw= github.com/fzipp/gocyclo v0.3.1/go.mod h1:DJHO6AUmbdqj2ET4Z9iArSuwWgYDRryYt2wASxc7x3E= @@ -456,7 +436,6 @@ github.com/go-audio/wav v1.1.0/go.mod h1:mpe9qfwbScEbkd8uybLuIpTgHyrISw/OTuvjUW2 github.com/go-chi/chi/v5 v5.0.8 h1:lD+NLqFcAi1ovnVZpsnObHGW4xb4J8lNmoYVfECH1Y0= github.com/go-chi/chi/v5 v5.0.8/go.mod h1:DslCQbL2OYiznFReuXYUmQ2hGd1aDpCnlMNITLSKoi8= github.com/go-critic/go-critic v0.5.4/go.mod h1:cjB4YGw+n/+X8gREApej7150Uyy1Tg8If6F2XOAUXNE= -github.com/go-critic/go-critic v0.5.5/go.mod h1:eMs1Oc/oIP+CYNVN09M+XZYffIPuRHawxzlggAPN9Kk= github.com/go-critic/go-critic v0.11.4 h1:O7kGOCx0NDIni4czrkRIXTnit0mkyKOCePh3My6OyEU= github.com/go-critic/go-critic v0.11.4/go.mod h1:2QAdo4iuLik5S9YG0rT4wcZ8QxwHYkrr6/2MWAiv/vc= github.com/go-fonts/dejavu v0.1.0 h1:JSajPXURYqpr+Cu8U9bt8K+XcACIHWqWrvWCKyeFmVQ= @@ -507,11 +486,9 @@ github.com/go-playground/validator/v10 v10.14.0 h1:vgvQWe3XCz3gIeFDm/HnTIbj6UGmg github.com/go-playground/validator/v10 v10.14.0/go.mod h1:9iXMNT7sEkjXb0I+enO7QXmzG6QCsPWY4zveKFVRSyU= github.com/go-quicktest/qt v1.101.0 h1:O1K29Txy5P2OK0dGo59b7b0LR6wKfIhttaAhHUyn7eI= github.com/go-quicktest/qt v1.101.0/go.mod h1:14Bz/f7NwaXPtdYEgzsx46kqSxVwTbzVZsDC26tQJow= -github.com/go-redis/redis v6.15.8+incompatible/go.mod h1:NAIEuMOZ/fxfXJIrKDQDz8wamY7mA7PouImQ2Jvg6kA= github.com/go-restruct/restruct v1.2.0-alpha.0.20210525045353-983b86fa188e h1:PIFVUcdZ9OADg9XAsN0I8OzUzmYXHU+2msP2X7ST/fo= github.com/go-restruct/restruct v1.2.0-alpha.0.20210525045353-983b86fa188e/go.mod h1:KqrpKpn4M8OLznErihXTGLlsXFGeLxHUrLRRI/1YjGk= github.com/go-sql-driver/mysql v1.4.0/go.mod h1:zAC/RDZ24gD3HViQzih4MyKcchzm+sOG5ZlKdlhCg5w= -github.com/go-sql-driver/mysql v1.5.0/go.mod h1:DCzpHaOWr8IXmIStZouvnhqoel9Qv2LBy8hT2VhHyBg= github.com/go-stack/stack v1.8.0/go.mod h1:v0f6uXyyMGvRgIKkXu+yp6POWl0qKG85gN/melR3HDY= github.com/go-task/slim-sprig/v3 v3.0.0 h1:sUs3vkvUymDpBKi3qH1YSqBQk9+9D/8M2mN1vB6EwHI= github.com/go-task/slim-sprig/v3 v3.0.0/go.mod h1:W848ghGpv3Qj3dhTPRyJypKRiqCdHZiAzKg9hl15HA8= @@ -574,7 +551,6 @@ github.com/gogo/googleapis v1.1.0/go.mod h1:gf4bu3Q80BeJ6H1S1vYPm8/ELATdvryBaNFG github.com/gogo/protobuf v1.1.1/go.mod h1:r8qH/GZQm5c6nD/R0oafs1akxWv10x8SbQlK7atdtwQ= github.com/gogo/protobuf v1.2.0/go.mod h1:r8qH/GZQm5c6nD/R0oafs1akxWv10x8SbQlK7atdtwQ= github.com/gogo/protobuf v1.2.1/go.mod h1:hp+jE20tsWTFYpLwKvXlhS1hjn+gTNwPg2I6zVXpSg4= -github.com/gogo/protobuf v1.3.0/go.mod h1:SlYgWuQ5SjCEi6WLHjHCa1yvBfUnHcTbrrZtXPKa29o= github.com/gogo/protobuf v1.3.1/go.mod h1:SlYgWuQ5SjCEi6WLHjHCa1yvBfUnHcTbrrZtXPKa29o= github.com/gogo/protobuf v1.3.2 h1:Ov1cvc58UF3b5XjBnZv7+opcTcQFZebYjWzi34vdm4Q= github.com/gogo/protobuf v1.3.2/go.mod h1:P1XiOD3dCwIKUDQYPy72D8LYyHL2YPYrpS2s69NZV8Q= @@ -601,7 +577,6 @@ github.com/golang/mock v1.4.0/go.mod h1:UOMv5ysSaYNkG+OFQykRIcU/QvvxJf3p21QfJ2Bt github.com/golang/mock v1.4.1/go.mod h1:UOMv5ysSaYNkG+OFQykRIcU/QvvxJf3p21QfJ2Bt3cw= github.com/golang/mock v1.4.3/go.mod h1:UOMv5ysSaYNkG+OFQykRIcU/QvvxJf3p21QfJ2Bt3cw= github.com/golang/mock v1.4.4/go.mod h1:l3mdAwkq5BuhzHwde/uurv3sEJeZMXNpwsxVWU71h+4= -github.com/golang/protobuf v1.1.0/go.mod h1:6lQm79b+lXiMfvg/cZm0SGofjICqVBUtrP5yJMmIC1U= github.com/golang/protobuf v1.2.0/go.mod h1:6lQm79b+lXiMfvg/cZm0SGofjICqVBUtrP5yJMmIC1U= github.com/golang/protobuf v1.3.1/go.mod h1:6lQm79b+lXiMfvg/cZm0SGofjICqVBUtrP5yJMmIC1U= github.com/golang/protobuf v1.3.2/go.mod h1:6lQm79b+lXiMfvg/cZm0SGofjICqVBUtrP5yJMmIC1U= @@ -632,7 +607,6 @@ github.com/golangci/gofmt v0.0.0-20190930125516-244bba706f1a/go.mod h1:9qCChq59u github.com/golangci/gofmt v0.0.0-20240816233607-d8596aa466a9 h1:/1322Qns6BtQxUZDTAT4SdcoxknUki7IAoK4SAXr8ME= github.com/golangci/gofmt v0.0.0-20240816233607-d8596aa466a9/go.mod h1:Oesb/0uFAyWoaw1U1qS5zyjCg5NP9C9iwjnI4tIsXEE= github.com/golangci/golangci-lint v1.38.0/go.mod h1:Knp/sd5ATrVp7EOzWzwIIFH+c8hUfpW+oOQb8NvdZDo= -github.com/golangci/golangci-lint v1.39.0/go.mod h1:mzMK3FGyk8LKTOxpRDcDqxwHVudnYemESTt5rpUxqCM= github.com/golangci/golangci-lint v1.61.0 h1:VvbOLaRVWmyxCnUIMTbf1kDsaJbTzH20FAMXTAlQGu8= github.com/golangci/golangci-lint v1.61.0/go.mod h1:e4lztIrJJgLPhWvFPDkhiMwEFRrWlmFbrZea3FsJyN8= github.com/golangci/lint-1 v0.0.0-20191013205115-297bf364a8e0/go.mod h1:66R6K6P6VWk9I95jvqGxkqJxVWGFy9XlDwLwVz1RCFg= @@ -654,8 +628,6 @@ github.com/gonuts/binary v0.2.0 h1:caITwMWAoQWlL0RNvv2lTU/AHqAJlVuu6nZmNgfbKW4= github.com/gonuts/binary v0.2.0/go.mod h1:kM+CtBrCGDSKdv8WXTuCUsw+loiy8f/QEI8YCCC0M/E= github.com/google/btree v0.0.0-20180813153112-4030bb1f1f0c/go.mod h1:lNA+9X1NB3Zf8V7Ke586lFgjr2dZNuvo3lPJSGZ5JPQ= github.com/google/btree v1.0.0/go.mod h1:lNA+9X1NB3Zf8V7Ke586lFgjr2dZNuvo3lPJSGZ5JPQ= -github.com/google/certificate-transparency-go v1.0.21/go.mod h1:QeJfpSbVSfYc7RgB3gJFj9cbuQMMchQxrWXz8Ruopmg= -github.com/google/certificate-transparency-go v1.1.1/go.mod h1:FDKqPvSXawb2ecErVRrD+nfy23RCzyl7eqVCEmlT1Zs= github.com/google/flatbuffers v1.11.0/go.mod h1:1AeVuKshWv4vARoZatz6mlQ0JxURH0Kv5+zNeJKJCa8= github.com/google/flatbuffers v2.0.6+incompatible h1:XHFReMv7nFFusa+CEokzWbzaYocKXI6C7hdU5Kgh9Lw= github.com/google/flatbuffers v2.0.6+incompatible/go.mod h1:1AeVuKshWv4vARoZatz6mlQ0JxURH0Kv5+zNeJKJCa8= @@ -688,7 +660,6 @@ github.com/google/pprof v0.0.0-20191218002539-d4f498aebedc/go.mod h1:ZgVRPoUq/hf github.com/google/pprof v0.0.0-20200212024743-f11f1df84d12/go.mod h1:ZgVRPoUq/hfqzAqh7sHMqb3I9Rq5C59dIz2SbBwJ4eM= github.com/google/pprof v0.0.0-20200229191704-1ebb73c60ed3/go.mod h1:ZgVRPoUq/hfqzAqh7sHMqb3I9Rq5C59dIz2SbBwJ4eM= github.com/google/pprof v0.0.0-20200430221834-fc25d7d30c6d/go.mod h1:ZgVRPoUq/hfqzAqh7sHMqb3I9Rq5C59dIz2SbBwJ4eM= -github.com/google/pprof v0.0.0-20200507031123-427632fa3b1c/go.mod h1:ZgVRPoUq/hfqzAqh7sHMqb3I9Rq5C59dIz2SbBwJ4eM= github.com/google/pprof v0.0.0-20200708004538-1a94d8640e99/go.mod h1:ZgVRPoUq/hfqzAqh7sHMqb3I9Rq5C59dIz2SbBwJ4eM= github.com/google/pprof v0.0.0-20211214055906-6f57359322fd/go.mod h1:KgnwoLYCZ8IQu3XUZ8Nc/bM9CCZFOyjUNOSygVozoDg= github.com/google/pprof v0.0.0-20240827171923-fa2c70bbbfe5 h1:5iH8iuqE5apketRbSFBy+X1V0o+l+8NF1avt4HWl7cA= @@ -698,8 +669,6 @@ github.com/google/s2a-go v0.1.8 h1:zZDs9gcbt9ZPLV0ndSyQk6Kacx2g/X+SKYovpnz3SMM= github.com/google/s2a-go v0.1.8/go.mod h1:6iNWHTpQ+nfNRN5E00MSdfDwVesa8hhS32PhPO8deJA= github.com/google/shlex v0.0.0-20191202100458-e7afc7fbc510 h1:El6M4kTTCOh6aBiKaUGG7oYTSPP8MxqL4YI3kZKwcP4= github.com/google/shlex v0.0.0-20191202100458-e7afc7fbc510/go.mod h1:pupxD2MaaD3pAXIBCelhxNneeOaAeabZDe5s4K6zSpQ= -github.com/google/trillian v1.3.11/go.mod h1:0tPraVHrSDkA3BO6vKX67zgLXs6SsOAbHEivX+9mPgw= -github.com/google/uuid v0.0.0-20161128191214-064e2069ce9c/go.mod h1:TIyPZe4MgqvfeYDBFedMoGGpEw/LqOeaOT+nhxU+yHo= github.com/google/uuid v1.0.0/go.mod h1:TIyPZe4MgqvfeYDBFedMoGGpEw/LqOeaOT+nhxU+yHo= github.com/google/uuid v1.1.1/go.mod h1:TIyPZe4MgqvfeYDBFedMoGGpEw/LqOeaOT+nhxU+yHo= github.com/google/uuid v1.1.2/go.mod h1:TIyPZe4MgqvfeYDBFedMoGGpEw/LqOeaOT+nhxU+yHo= @@ -713,17 +682,14 @@ github.com/googleapis/gax-go/v2 v2.0.5/go.mod h1:DWXyrwAJ9X0FpwwEdw+IPEYBICEFu5m github.com/googleapis/gax-go/v2 v2.13.0 h1:yitjD5f7jQHhyDsnhKEBU52NdvvdSeGzlAnDPT0hH1s= github.com/googleapis/gax-go/v2 v2.13.0/go.mod h1:Z/fvTZXF8/uw7Xu5GuslPw+bplx6SS338j1Is2S+B7A= github.com/gookit/color v1.3.6/go.mod h1:R3ogXq2B9rTbXoSHJ1HyUVAZ3poOJHpd9nQmyGZsfvQ= -github.com/gookit/color v1.3.8/go.mod h1:R3ogXq2B9rTbXoSHJ1HyUVAZ3poOJHpd9nQmyGZsfvQ= github.com/gopherjs/gopherjs v0.0.0-20181017120253-0766667cb4d1/go.mod h1:wJfORRmW1u3UXTncJ5qlYoELFm8eSnnEO6hX4iZ3EWY= github.com/gordonklaus/ineffassign v0.0.0-20200309095847-7953dde2c7bf/go.mod h1:cuNKsD1zp2v6XfE/orVX2QE1LC+i254ceGcVeDT3pTU= github.com/gordonklaus/ineffassign v0.0.0-20210225214923-2e10b2664254/go.mod h1:M9mZEtGIsR1oDaZagNPNG9iq9n2HrhZ17dsXk73V3Lw= github.com/gordonklaus/ineffassign v0.1.0 h1:y2Gd/9I7MdY1oEIt+n+rowjBNDcLQq3RsH5hwJd0f9s= github.com/gordonklaus/ineffassign v0.1.0/go.mod h1:Qcp2HIAYhR7mNUVSIxZww3Guk4it82ghYcEXIAk+QT0= -github.com/gorhill/cronexpr v0.0.0-20180427100037-88b0669f7d75/go.mod h1:g2644b03hfBX9Ov0ZBDgXXens4rxSxmqFBbhvKv2yVA= github.com/gorilla/context v1.1.1/go.mod h1:kBGZzfjB9CEq2AlWe17Uuf7NDRt0dE0s8S51q0aT7Yg= github.com/gorilla/mux v1.6.2/go.mod h1:1lud6UwP+6orDFRuTfBEV8e9/aOM/c4fVVCaMa2zaAs= github.com/gorilla/mux v1.7.3/go.mod h1:1lud6UwP+6orDFRuTfBEV8e9/aOM/c4fVVCaMa2zaAs= -github.com/gorilla/mux v1.8.0/go.mod h1:DVbg23sWSpFRCP0SfiEN6jmj59UnW/n46BH5rLB71So= github.com/gorilla/securecookie v1.1.1 h1:miw7JPhV+b/lAHSXz4qd/nN9jRiAFV5FwjeKyCS8BvQ= github.com/gorilla/securecookie v1.1.1/go.mod h1:ra0sb63/xPlUeL+yeDciTfxMRAA+MP+HVt/4epWDjd4= github.com/gorilla/sessions v1.2.0/go.mod h1:dk2InVEVJ0sfLlnXv9EAgkf6ecYs/i80K/zI+bUmuGM= @@ -749,7 +715,6 @@ github.com/gostaticanalysis/nilerr v0.1.1/go.mod h1:wZYb6YI5YAxxq0i1+VJbY0s2YONW github.com/gostaticanalysis/testutil v0.3.1-0.20210208050101-bfb5c8eec0e4/go.mod h1:D+FIZ+7OahH3ePw/izIEeH5I06eKs1IKI4Xr64/Am3M= github.com/gostaticanalysis/testutil v0.4.0 h1:nhdCmubdmDF6VEatUNjgUZBJKWRqugoISdUv3PPQgHY= github.com/gostaticanalysis/testutil v0.4.0/go.mod h1:bLIoPefWXrRi/ssLFWX1dx7Repi5x3CuviD3dgAZaBU= -github.com/gregjones/httpcache v0.0.0-20190611155906-901d90724c79/go.mod h1:FecbI9+v66THATjSRHfNgh1IVFe/9kFxbXtjV0ctIMA= github.com/grpc-ecosystem/go-grpc-middleware v1.0.0/go.mod h1:FiyG127CGDf3tlThmgyCl78X/SZQqEOJBCDaAfeWzPs= github.com/grpc-ecosystem/go-grpc-middleware v1.0.1-0.20190118093823-f849b5445de4/go.mod h1:FiyG127CGDf3tlThmgyCl78X/SZQqEOJBCDaAfeWzPs= github.com/grpc-ecosystem/go-grpc-middleware v1.2.2/go.mod h1:EaizFBKfUKtMIF5iaDEhniwNedqGo9FuLFzppDr3uwI= @@ -758,7 +723,6 @@ github.com/grpc-ecosystem/go-grpc-middleware v1.4.0/go.mod h1:g5qyo/la0ALbONm6Vb github.com/grpc-ecosystem/go-grpc-prometheus v1.2.0/go.mod h1:8NvIoxWQoOIhqOTXgfV/d3M/q6VIi02HzZEHgUlZvzk= github.com/grpc-ecosystem/grpc-gateway v1.9.0/go.mod h1:vNeuVxBJEsws4ogUvrchl83t/GYV9WGTSLVdBhOQFDY= github.com/grpc-ecosystem/grpc-gateway v1.9.5/go.mod h1:vNeuVxBJEsws4ogUvrchl83t/GYV9WGTSLVdBhOQFDY= -github.com/grpc-ecosystem/grpc-gateway v1.12.1/go.mod h1:8XEsbTttt/W+VvjtQhLACqCisSPWTxCZ7sBRjU6iH9c= github.com/grpc-ecosystem/grpc-gateway v1.16.0/go.mod h1:BDjrQk3hbvj6Nolgz8mAMFbcEtjT1g+wF4CSlocrBnw= github.com/grpc-ecosystem/grpc-gateway/v2 v2.15.2 h1:gDLXvp5S9izjldquuoAhDzccbskOL6tDC5jMSyx3zxE= github.com/grpc-ecosystem/grpc-gateway/v2 v2.15.2/go.mod h1:7pdNwVWBBHGiCxa9lAszqCJMbfTISJ7oMftp8+UGV08= @@ -793,8 +757,6 @@ github.com/hashicorp/serf v0.8.2/go.mod h1:6hOLApaqBFA1NXqRQAsxw9QxuDEvNxSQRwA/J github.com/hexops/gotextdiff v1.0.3 h1:gitA9+qJrrTCsiCl7+kh75nPqQt1cx4ZkudSTLoUqJM= github.com/hexops/gotextdiff v1.0.3/go.mod h1:pSWU5MAI3yDq+fZBTazCSJysOMbxWL1BSow5/V2vxeg= github.com/hpcloud/tail v1.0.0/go.mod h1:ab1qPbhIpdTxEkNHXyeSf5vhxWSCs/tWer42PpOxQnU= -github.com/huandu/xstrings v1.0.0/go.mod h1:4qWG/gcEcfX4z/mBDHJ++3ReCw9ibxbsNJbcucJdbSo= -github.com/huandu/xstrings v1.2.0/go.mod h1:DvyZB1rfVYsBIigL8HwpZgxHwXozlTgGqn63UyNX5k4= github.com/huandu/xstrings v1.3.2 h1:L18LIDzqlW6xN2rEkpdV8+oL/IXWJ1APd+vsdYy4Wdw= github.com/huandu/xstrings v1.3.2/go.mod h1:y5/lhBue+AyNmUVz9RLU9xbLR0o4KIIExikq4ovT0aE= github.com/hudl/fargo v1.3.0/go.mod h1:y3CKSmjA+wD2gak7sUSXTAoopbhU08POFhmITJgmKTg= @@ -802,8 +764,6 @@ github.com/iancoleman/orderedmap v0.0.0-20190318233801-ac98e3ecb4b0 h1:i462o439Z github.com/iancoleman/orderedmap v0.0.0-20190318233801-ac98e3ecb4b0/go.mod h1:N0Wam8K1arqPXNWjMo21EXnBPOPp36vB07FNRdD2geA= github.com/ianlancetaylor/demangle v0.0.0-20181102032728-5e5cf60278f6/go.mod h1:aSSvb/t6k1mPoxDqO4vJh6VOCGPwU4O0C2/Eqndh1Sc= github.com/ianlancetaylor/demangle v0.0.0-20210905161508-09a460cdf81d/go.mod h1:aYm2/VgdVmcIU8iMfdMvDMsRAQjcfZSKFby6HOFvi/w= -github.com/imdario/mergo v0.3.4/go.mod h1:2EnlNZ0deacrJVfApfmtdGgDfMuh/nq6Ok1EcJh5FfA= -github.com/imdario/mergo v0.3.8/go.mod h1:2EnlNZ0deacrJVfApfmtdGgDfMuh/nq6Ok1EcJh5FfA= github.com/imdario/mergo v0.3.12 h1:b6R2BslTbIEToALKP7LxUvijTsNI9TAe80pLWN2g/HU= github.com/imdario/mergo v0.3.12/go.mod h1:jmQim1M+e3UYxmgPu/WyfjB3N3VflVyUjjjwH0dnCYA= github.com/improbable-eng/grpc-web v0.15.0 h1:BN+7z6uNXZ1tQGcNAuaU1YjsLTApzkjt2tzCixLaUPQ= @@ -824,12 +784,10 @@ github.com/jessevdk/go-flags v1.4.0/go.mod h1:4FA24M0QyGHXBuZZK/XkWh8h0e1EYbRYJS github.com/jgautheron/goconst v1.4.0/go.mod h1:aAosetZ5zaeC/2EfMeRswtxUFBpe2Hr7HzkgX4fanO4= github.com/jgautheron/goconst v1.7.1 h1:VpdAG7Ca7yvvJk5n8dMwQhfEZJh95kl/Hl9S1OI5Jkk= github.com/jgautheron/goconst v1.7.1/go.mod h1:aAosetZ5zaeC/2EfMeRswtxUFBpe2Hr7HzkgX4fanO4= -github.com/jhump/protoreflect v1.6.1/go.mod h1:RZQ/lnuN+zqeRVpQigTwO6o0AJUkxbnSnpuG7toUTG4= github.com/jhump/protoreflect v1.10.3/go.mod h1:7GcYQDdMU/O/BBrl/cX6PNHpXh6cenjd8pneu5yW7Tg= github.com/jhump/protoreflect v1.15.1 h1:HUMERORf3I3ZdX05WaQ6MIpd/NJ434hTp5YiKgfCL6c= github.com/jhump/protoreflect v1.15.1/go.mod h1:jD/2GMKKE6OqX8qTjhADU1e6DShO+gavG9e0Q693nKo= github.com/jingyugao/rowserrcheck v0.0.0-20210130005344-c6a0c12dd98d/go.mod h1:/EZlaYCnEX24i7qdVhT9du5JrtFWYRQr67bVgR7JJC8= -github.com/jingyugao/rowserrcheck v0.0.0-20210315055705-d907ca737bb1/go.mod h1:TOQpc2SLx6huPfoFGK3UOnEG+u02D3C1GeosjupAKCA= github.com/jingyugao/rowserrcheck v1.1.1 h1:zibz55j/MJtLsjP1OF4bSdgXxwL1b+Vn7Tjzq7gFzUs= github.com/jingyugao/rowserrcheck v1.1.1/go.mod h1:4yvlZSDb3IyDTUZJUmpZfm2Hwok+Dtp+nu2qOq+er9c= github.com/jirfag/go-printf-func-name v0.0.0-20200119135958-7558a9eaa5af h1:KA9BjwUk7KlCh6S9EAGWBt1oExIUv9WyNCiRz5amv48= @@ -843,7 +801,6 @@ github.com/jmespath/go-jmespath/internal/testify v1.5.1 h1:shLQSRRSCCPj3f2gpwzGw github.com/jmespath/go-jmespath/internal/testify v1.5.1/go.mod h1:L3OGu8Wl2/fWfCI6z80xFu9LTZmf1ZRjMHUOPmWr69U= github.com/jmoiron/sqlx v1.2.0/go.mod h1:1FEQNm3xlJgrMD+FBdI9+xvCksHtbpVBBw5dYhBSsks= github.com/jonboulle/clockwork v0.1.0/go.mod h1:Ii8DK3G1RaLaWxj9trq07+26W01tbo22gdxWY5EU2bo= -github.com/jonboulle/clockwork v0.2.0/go.mod h1:Pkfl5aHPm1nk2H9h0bjmnJD/BcgbGXUBGnn1kMkgxc8= github.com/jonboulle/clockwork v0.3.0 h1:9BSCMi8C+0qdApAp4auwX0RkLGUjs956h0EkuQymUhg= github.com/jonboulle/clockwork v0.3.0/go.mod h1:Pkfl5aHPm1nk2H9h0bjmnJD/BcgbGXUBGnn1kMkgxc8= github.com/jpillora/backoff v1.0.0/go.mod h1:J/6gKK9jxlEcS3zixgDgUAsiuZ7yrSoa/FX5e0EB2j4= @@ -858,15 +815,12 @@ github.com/json-iterator/go v1.1.12/go.mod h1:e30LSqwooZae/UwlEbR2852Gd8hjQvJoHm github.com/jstemmer/go-junit-report v0.0.0-20190106144839-af01ea7f8024/go.mod h1:6v2b51hI/fHJwM22ozAgKL4VKDeJcHhJFhtBdhmNjmU= github.com/jstemmer/go-junit-report v0.9.1/go.mod h1:Brl9GWCQeLvo8nXZwPNNblvFj/XSXhF0NWZEnDohbsk= github.com/jtolds/gls v4.20.0+incompatible/go.mod h1:QJZ7F/aHp+rZTRtaJ1ow/lLfFfVYBRgL+9YlvaHOwJU= -github.com/juju/ratelimit v1.0.1/go.mod h1:qapgC/Gy+xNh9UxzV13HGGl/6UXNN+ct+vwSgWNm/qk= github.com/julienschmidt/httprouter v1.2.0/go.mod h1:SYymIcj16QtmaHHD7aYtjjsJG7VTCxuUUipMqKk8s4w= github.com/julienschmidt/httprouter v1.3.0/go.mod h1:JR6WtHb+2LUe8TCKY3cZOxFyyO8IZAc4RVcycCCAKdM= github.com/julz/importas v0.0.0-20210226073942-60b4fa260dd0/go.mod h1:oSFU2R4XK/P7kNBrnL/FEQlDGN1/6WoxXEjSSXO0DV0= -github.com/julz/importas v0.0.0-20210228071311-d0bf5cb4e1db/go.mod h1:oSFU2R4XK/P7kNBrnL/FEQlDGN1/6WoxXEjSSXO0DV0= github.com/julz/importas v0.1.0 h1:F78HnrsjY3cR7j0etXy5+TU1Zuy7Xt08X/1aJnH5xXY= github.com/julz/importas v0.1.0/go.mod h1:oSFU2R4XK/P7kNBrnL/FEQlDGN1/6WoxXEjSSXO0DV0= github.com/jung-kurt/gofpdf v1.0.0/go.mod h1:7Id9E/uU8ce6rXgefFLlgrJj/GYY22cpxn+r32jIOes= -github.com/k0kubun/colorstring v0.0.0-20150214042306-9440f1994b88/go.mod h1:3w7q1U84EfirKl04SVQ/s7nPm1ZPhiXd34z40TNz36k= github.com/karamaru-alpha/copyloopvar v1.1.0 h1:x7gNyKcC2vRBO1H2Mks5u1VxQtYvFiym7fCjIP8RPos= github.com/karamaru-alpha/copyloopvar v1.1.0/go.mod h1:u7CIfztblY0jZLOQZgH3oYsJzpC2A7S6u/lfgSXHy0k= github.com/kellydunn/golang-geo v0.7.0 h1:A5j0/BvNgGwY6Yb6inXQxzYwlPHc6WVZR+MrarZYNNg= @@ -895,7 +849,6 @@ github.com/klauspost/cpuid/v2 v2.2.4/go.mod h1:RVVoqg1df56z8g3pUjL/3lE5UfnlrJX8t github.com/klauspost/pgzip v1.2.6 h1:8RXeL5crjEUFnR2/Sn6GJNWtSQ3Dk8pq4CL3jvdDyjU= github.com/klauspost/pgzip v1.2.6/go.mod h1:Ch1tH69qFZu15pkjo5kYi6mth2Zzwzt50oCQKQE9RUs= github.com/konsorten/go-windows-terminal-sequences v1.0.1/go.mod h1:T0+1ngSBFLxvqU3pZ+m/2kptfBszLMUkC4ZK/EgS/cQ= -github.com/konsorten/go-windows-terminal-sequences v1.0.2/go.mod h1:T0+1ngSBFLxvqU3pZ+m/2kptfBszLMUkC4ZK/EgS/cQ= github.com/konsorten/go-windows-terminal-sequences v1.0.3/go.mod h1:T0+1ngSBFLxvqU3pZ+m/2kptfBszLMUkC4ZK/EgS/cQ= github.com/kr/fs v0.1.0/go.mod h1:FFnZGqtBN9Gxj7eW1uZ42v5BccTP0vu6NEaFoC2HwRg= github.com/kr/logfmt v0.0.0-20140226030751-b84e30acd515/go.mod h1:+0opPa2QZZtGFBFZlji/RkVcI2GknAs/DXo4wKdlNEc= @@ -922,7 +875,6 @@ github.com/kyoh86/exportloopref v0.1.11 h1:1Z0bcmTypkL3Q4k+IDHMWTcnCliEZcaPiIe0/ github.com/kyoh86/exportloopref v0.1.11/go.mod h1:qkV4UF1zGl6EkF1ox8L5t9SwyeBAZ3qLMd6up458uqA= github.com/lasiar/canonicalheader v1.1.1 h1:wC+dY9ZfiqiPwAexUApFush/csSPXeIi4QqyxXmng8I= github.com/lasiar/canonicalheader v1.1.1/go.mod h1:cXkb3Dlk6XXy+8MVQnF23CYKWlyA7kfQhSw2CcZtZb0= -github.com/ldez/gomoddirectives v0.2.1/go.mod h1:sGicqkRgBOg//JfpXwkB9Hj0X5RyJ7mlACM5B9f6Me4= github.com/ldez/gomoddirectives v0.2.4 h1:j3YjBIjEBbqZ0NKtBNzr8rtMHTOrLPeiwTkfUJZ3alg= github.com/ldez/gomoddirectives v0.2.4/go.mod h1:oWu9i62VcQDYp9EQ0ONTfqLNh+mDLWWDO+SO0qSQw5g= github.com/ldez/tagliatelle v0.5.0 h1:epgfuYt9v0CG3fms0pEgIMNPuFf/LpPIfjk4kyqSioo= @@ -945,9 +897,7 @@ github.com/lestrrat-go/jwx v1.2.29/go.mod h1:hU8k2l6WF0ncx20uQdOmik/Gjg6E3/wIRtX github.com/lestrrat-go/option v1.0.0/go.mod h1:5ZHFbivi4xwXxhxY9XHDe2FHo6/Z7WWmtT7T5nBBp3I= github.com/lestrrat-go/option v1.0.1 h1:oAzP2fvZGQKWkvHa1/SAcFolBEca1oN+mQ7eooNBEYU= github.com/lestrrat-go/option v1.0.1/go.mod h1:5ZHFbivi4xwXxhxY9XHDe2FHo6/Z7WWmtT7T5nBBp3I= -github.com/letsencrypt/pkcs11key/v4 v4.0.0/go.mod h1:EFUvBDay26dErnNb70Nd0/VW3tJiIbETBPTl9ATXQag= github.com/lib/pq v1.0.0/go.mod h1:5WUZQaWbwv1U+lTReE5YruASi9Al49XbQIvNi/34Woo= -github.com/lib/pq v1.8.0/go.mod h1:AlVN5x4E4T544tWzH6hKfbfQvm3HdbOxrmggDNAPY9o= github.com/lib/pq v1.9.0/go.mod h1:AlVN5x4E4T544tWzH6hKfbfQvm3HdbOxrmggDNAPY9o= github.com/lib/pq v1.10.9 h1:YXG7RB+JIjhP29X+OtkiDnYaXQwpS4JEWq7dtCCRUEw= github.com/lib/pq v1.10.9/go.mod h1:AlVN5x4E4T544tWzH6hKfbfQvm3HdbOxrmggDNAPY9o= @@ -965,7 +915,6 @@ github.com/lyft/protoc-gen-validate v0.0.13/go.mod h1:XbGvPuh87YZc5TdIa2/I4pLk0Q github.com/macabu/inamedparam v0.1.3 h1:2tk/phHkMlEL/1GNe/Yf6kkR/hkcUdAEY3L0hjYV1Mk= github.com/macabu/inamedparam v0.1.3/go.mod h1:93FLICAIk/quk7eaPPQvbzihUdn/QkGDwIZEoLtpH6I= github.com/magefile/mage v1.10.0/go.mod h1:z5UZb/iS3GoOSn0JgWuiw7dxlurVYTu+/jHXqQg881A= -github.com/magiconair/properties v1.8.0/go.mod h1:PppfXfuXeibc/6YijjN8zIbojt8czPbwD3XqdrwzmxQ= github.com/magiconair/properties v1.8.1/go.mod h1:PppfXfuXeibc/6YijjN8zIbojt8czPbwD3XqdrwzmxQ= github.com/magiconair/properties v1.8.6 h1:5ibWZ6iY0NctNGWo87LalDlEZ6R41TqbbDamhfG/Qzo= github.com/magiconair/properties v1.8.6/go.mod h1:y3VJvCyxH9uVvJTWEGAELF3aiYNyPKd5NZ3oSwXrF60= @@ -989,7 +938,6 @@ github.com/mattn/go-colorable v0.1.13/go.mod h1:7S9/ev0klgBDR4GtXTXX8a3vIGJpMovk github.com/mattn/go-isatty v0.0.3/go.mod h1:M+lRXTBqGeGNdLjl/ufCoiOlB5xdOkqRJdNxMWT7Zi4= github.com/mattn/go-isatty v0.0.4/go.mod h1:M+lRXTBqGeGNdLjl/ufCoiOlB5xdOkqRJdNxMWT7Zi4= github.com/mattn/go-isatty v0.0.8/go.mod h1:Iq45c/XA43vh69/j3iqttzPXn0bhXyGjM0Hdxcsrc5s= -github.com/mattn/go-isatty v0.0.10/go.mod h1:qgIWMr58cqv1PHHyhnkY9lrL7etaEgOFcMEpPG5Rm84= github.com/mattn/go-isatty v0.0.11/go.mod h1:PhnuNfih5lzO57/f3n+odYbM4JtupLOxQOAqxQCu2WE= github.com/mattn/go-isatty v0.0.12/go.mod h1:cbi8OIDigv2wuxKPP5vlRcQ1OAZbq2CE4Kysco4FUpU= github.com/mattn/go-isatty v0.0.14/go.mod h1:7GGIvUiUoEMVVmxf/4nioHXj79iQHKdU27kJ6hsGG94= @@ -999,8 +947,6 @@ github.com/mattn/go-isatty v0.0.20/go.mod h1:W+V8PltTTMOvKvAeJH7IuucS94S2C6jfK/D github.com/mattn/go-localereader v0.0.1 h1:ygSAOl7ZXTx4RdPYinUpg6W99U8jWvWi9Ye2JC/oIi4= github.com/mattn/go-localereader v0.0.1/go.mod h1:8fBrzywKY7BI3czFoHkuzRoWE9C+EiG4R1k4Cjx5p88= github.com/mattn/go-runewidth v0.0.2/go.mod h1:LwmH8dsx7+W8Uxz3IHJYH5QSwggIsqBzpuz5H//U1FU= -github.com/mattn/go-runewidth v0.0.4/go.mod h1:LwmH8dsx7+W8Uxz3IHJYH5QSwggIsqBzpuz5H//U1FU= -github.com/mattn/go-runewidth v0.0.6/go.mod h1:H031xJmbD/WCDINGzjvQ9THkh0rPKHF+m2gUSrubnMI= github.com/mattn/go-runewidth v0.0.7/go.mod h1:H031xJmbD/WCDINGzjvQ9THkh0rPKHF+m2gUSrubnMI= github.com/mattn/go-runewidth v0.0.9/go.mod h1:H031xJmbD/WCDINGzjvQ9THkh0rPKHF+m2gUSrubnMI= github.com/mattn/go-runewidth v0.0.13/go.mod h1:Jdepj2loyihRzMpdS35Xk/zdY8IAYHsh153qUoGf23w= @@ -1014,18 +960,13 @@ github.com/matttproud/golang_protobuf_extensions v1.0.4/go.mod h1:BSXmuO+STAnVfr github.com/mbilski/exhaustivestruct v1.2.0/go.mod h1:OeTBVxQWoEmB2J2JCHmXWPJ0aksxSUOUy+nvtVEfzXc= github.com/mgechev/dots v0.0.0-20190921121421-c36f7dcfbb81/go.mod h1:KQ7+USdGKfpPjXk4Ga+5XxQM4Lm4e3gAogrreFAYpOg= github.com/mgechev/revive v1.0.3/go.mod h1:POGGZagSo/0frdr7VeAifzS5Uka0d0GPiM35MsTO8nE= -github.com/mgechev/revive v1.0.5/go.mod h1:tSw34BaGZ0iF+oVKDOjq1/LuxGifgW7shaJ6+dBYFXg= github.com/mgechev/revive v1.3.9 h1:18Y3R4a2USSBF+QZKFQwVkBROUda7uoBlkEuBD+YD1A= github.com/mgechev/revive v1.3.9/go.mod h1:+uxEIr5UH0TjXWHTno3xh4u7eg6jDpXKzQccA9UGhHU= github.com/miekg/dns v1.0.14/go.mod h1:W1PPwlIAgtquWBMBEV9nkV9Cazfe8ScdGz/Lj7v3Nrg= -github.com/miekg/dns v1.1.35/go.mod h1:KNUDUusw/aVsxyTYZM1oqvCicbwhgbNgztCETuNZ7xM= github.com/miekg/dns v1.1.41/go.mod h1:p6aan82bvRIyn+zDIv9xYNUpwa73JcSh9BKwknJysuI= github.com/miekg/dns v1.1.53 h1:ZBkuHr5dxHtB1caEOlZTLPo7D3L3TWckgUUs/RHfDxw= github.com/miekg/dns v1.1.53/go.mod h1:uInx36IzPl7FYnDcMeVWxj9byh7DutNykX4G9Sj60FY= -github.com/miekg/pkcs11 v1.0.2/go.mod h1:XsNlhZGX73bx86s2hdc/FuaLm2CPZJemRLMA+WTFxgs= -github.com/miekg/pkcs11 v1.0.3/go.mod h1:XsNlhZGX73bx86s2hdc/FuaLm2CPZJemRLMA+WTFxgs= github.com/mitchellh/cli v1.0.0/go.mod h1:hNIlj7HEI86fIcpObd7a0FcrxTWetlwJDGcceTlRvqc= -github.com/mitchellh/copystructure v1.0.0/go.mod h1:SNtv71yrdKgLRyLFxmLdkAbkKEFWgYaq1OVrnRcwhnw= github.com/mitchellh/copystructure v1.2.0 h1:vpKXTN4ewci03Vljg/q9QvCGUDttBOGBIa15WveJJGw= github.com/mitchellh/copystructure v1.2.0/go.mod h1:qLl+cE2AmVv+CoeAwDPye/v+N2HKCj9FbZEVFJRxO9s= github.com/mitchellh/go-homedir v1.0.0/go.mod h1:SfyaCUpYCn1Vlf4IUYiD9fPX4A5wJrkLzIz1N1q0pr0= @@ -1041,8 +982,6 @@ github.com/mitchellh/mapstructure v0.0.0-20160808181253-ca63d7c062ee/go.mod h1:F github.com/mitchellh/mapstructure v1.1.2/go.mod h1:FVVH3fgwuzCH5S8UJGiWEs2h04kUh9fWfEaFds41c1Y= github.com/mitchellh/mapstructure v1.5.0 h1:jeMsZIYE/09sWLaz43PL7Gy6RuMjD2eJVyuac5Z2hdY= github.com/mitchellh/mapstructure v1.5.0/go.mod h1:bFUtVrKA4DC2yAKiSyO/QUcy7e+RRV2QTWOzhPopBRo= -github.com/mitchellh/reflectwalk v1.0.0/go.mod h1:mSTlrgnPZtwu0c4WaC2kGObEpuNDbx0jmZXqmk4esnw= -github.com/mitchellh/reflectwalk v1.0.1/go.mod h1:mSTlrgnPZtwu0c4WaC2kGObEpuNDbx0jmZXqmk4esnw= github.com/mitchellh/reflectwalk v1.0.2 h1:G2LzWKi524PWgd3mLHV8Y5k7s6XUvT0Gef6zxSIeXaQ= github.com/mitchellh/reflectwalk v1.0.2/go.mod h1:mSTlrgnPZtwu0c4WaC2kGObEpuNDbx0jmZXqmk4esnw= github.com/mkch/asserting v0.0.0-20190916092325-c18221b2f2b2 h1:ZuTZrURK+9dqhtVw11exJ65tjbh3DVXj4L5R1KnFAU8= @@ -1058,7 +997,6 @@ github.com/modern-go/reflect2 v0.0.0-20180701023420-4b7aa43c6742/go.mod h1:bx2lN github.com/modern-go/reflect2 v1.0.1/go.mod h1:bx2lNnkwVCuqBIxFjflWJWanXIb3RllmbCylyMrvgv0= github.com/modern-go/reflect2 v1.0.2 h1:xBagoLtFs94CBntxluKeaWgTMpvLxC4ur3nMaC9Gz0M= github.com/modern-go/reflect2 v1.0.2/go.mod h1:yWuevngMOJpCy52FWWMvUC8ws7m/LJsjYzDa0/r8luk= -github.com/mohae/deepcopy v0.0.0-20170929034955-c48cc78d4826/go.mod h1:TaXosZuwdSHYgviHp1DAtfrULt5eUgsSMsZf+YrPgl8= github.com/montanaflynn/stats v0.0.0-20171201202039-1bf9dbcd8cbe/go.mod h1:wL8QJuTMNUDYhXwkmfOly8iTdp5TEcJFWZD2D7SIkUc= github.com/montanaflynn/stats v0.7.0 h1:r3y12KyNxj/Sb/iOE46ws+3mS1+MZca1wlHQFPsY/JU= github.com/montanaflynn/stats v0.7.0/go.mod h1:etXPPgVO6n31NxCd9KQUMvCM+ve0ruNzt6R8Bnaayow= @@ -1067,9 +1005,7 @@ github.com/moricho/tparallel v0.3.2 h1:odr8aZVFA3NZrNybggMkYO3rgPRcqjeQUlBBFVxKH github.com/moricho/tparallel v0.3.2/go.mod h1:OQ+K3b4Ln3l2TZveGCywybl68glfLEwFGqvnjok8b+U= github.com/morikuni/aec v1.0.0 h1:nP9CBfwrvYnBRgY6qfDQkygYDmYwOilePFkwzv4dU8A= github.com/morikuni/aec v1.0.0/go.mod h1:BbKIizmSmc5MMPqRYbxO4ZU0S0+P200+tUnFx7PXmsc= -github.com/mozilla/scribe v0.0.0-20180711195314-fb71baf557c1/go.mod h1:FIczTrinKo8VaLxe6PWTPEXRXDIHz2QAwiaBaP5/4a8= github.com/mozilla/tls-observatory v0.0.0-20201209171846-0547674fceff/go.mod h1:SrKMQvPiws7F7iqYp8/TX+IhxCYhzr6N/1yb8cwHsGk= -github.com/mozilla/tls-observatory v0.0.0-20210209181001-cf43108d6880/go.mod h1:FUqVoUPHSEdDR0MnFM3Dh8AU0pZHLXUD127SAJGER/s= github.com/muesli/ansi v0.0.0-20230316100256-276c6243b2f6 h1:ZK8zHtRHOkbHy6Mmr5D264iyp3TiX5OmNcI5cIARiQI= github.com/muesli/ansi v0.0.0-20230316100256-276c6243b2f6/go.mod h1:CJlz5H+gyd6CUWT45Oy4q24RdLyn7Md9Vj2/ldJBSIo= github.com/muesli/cancelreader v0.2.2 h1:3I4Kt4BQjOR54NavqnDogx/MIoWBFa0StPA8ELUXHmA= @@ -1084,8 +1020,6 @@ github.com/muesli/termenv v0.15.3-0.20240618155329-98d742f6907a/go.mod h1:hxSnBB github.com/mwitkow/go-conntrack v0.0.0-20161129095857-cc309e4a2223/go.mod h1:qRWi+5nqEBWmkhHvq77mSJWrCKwh8bxhgT7d/eI7P4U= github.com/mwitkow/go-conntrack v0.0.0-20190716064945-2f068394615f h1:KUppIJq7/+SVif2QVs3tOP0zanoHgBEVAwHxUSIzRqU= github.com/mwitkow/go-conntrack v0.0.0-20190716064945-2f068394615f/go.mod h1:qRWi+5nqEBWmkhHvq77mSJWrCKwh8bxhgT7d/eI7P4U= -github.com/mwitkow/go-proto-validators v0.0.0-20180403085117-0950a7990007/go.mod h1:m2XC9Qq0AlmmVksL6FktJCdTYyLk7V3fKyp0sl1yWQo= -github.com/mwitkow/go-proto-validators v0.2.0/go.mod h1:ZfA1hW+UH/2ZHOWvQ3HnQaU0DtnpXu850MZiy+YUgcc= github.com/mwitkow/grpc-proxy v0.0.0-20181017164139-0f1106ef9c76/go.mod h1:x5OoJHDHqxHS801UIuhqGl6QdSAEJvtausosHSdazIo= github.com/nakabonne/nestif v0.3.0/go.mod h1:dI314BppzXjJ4HsCnbo7XzrJHPszZsjnk5wEBSYHI2c= github.com/nakabonne/nestif v0.3.1 h1:wm28nZjhQY5HyYPx+weN3Q65k6ilSBxDb8v5S81B81U= @@ -1100,14 +1034,12 @@ github.com/nats-io/nkeys v0.1.0/go.mod h1:xpnFELMwJABBLVhffcfd1MZx6VsNRFpEugbxzi github.com/nats-io/nkeys v0.1.3/go.mod h1:xpnFELMwJABBLVhffcfd1MZx6VsNRFpEugbxziKVo7w= github.com/nats-io/nuid v1.0.1/go.mod h1:19wcPz3Ph3q0Jbyiqsd0kePYG7A95tJPxeL+1OSON2c= github.com/nbutton23/zxcvbn-go v0.0.0-20201221231540-e56b841a3c88/go.mod h1:KSVJerMDfblTH7p5MZaTt+8zaT2iEk3AkVb9PQdZuE8= -github.com/nbutton23/zxcvbn-go v0.0.0-20210217022336-fa2cb2858354/go.mod h1:KSVJerMDfblTH7p5MZaTt+8zaT2iEk3AkVb9PQdZuE8= github.com/nfnt/resize v0.0.0-20180221191011-83c6a9932646 h1:zYyBkD/k9seD2A7fsi6Oo2LfFZAehjjQMERAvZLEDnQ= github.com/nfnt/resize v0.0.0-20180221191011-83c6a9932646/go.mod h1:jpp1/29i3P1S/RLdc7JQKbRpFeM1dOBd8T9ki5s+AY8= github.com/niemeyer/pretty v0.0.0-20200227124842-a10e7caefd8e/go.mod h1:zD1mROLANZcx1PVRCS0qkT7pwLkGfwJo4zjcN/Tysno= github.com/nishanths/exhaustive v0.1.0/go.mod h1:S1j9110vxV1ECdCudXRkeMnFQ/DQk9ajLT0Uf2MYZQQ= github.com/nishanths/exhaustive v0.12.0 h1:vIY9sALmw6T/yxiASewa4TQcFsVYZQQRUQJhKRf3Swg= github.com/nishanths/exhaustive v0.12.0/go.mod h1:mEZ95wPIZW+x8kC4TgC+9YCUgiST7ecevsVDTgc2obs= -github.com/nishanths/predeclared v0.0.0-20190419143655-18a43bb90ffc/go.mod h1:62PewwiQTlm/7Rj+cxVYqZvDIUc+JjZq6GHAC1fsObQ= github.com/nishanths/predeclared v0.0.0-20200524104333-86fad755b4d3/go.mod h1:nt3d53pc1VYcphSCIaYAJtnPYnr3Zyn8fMq2wvPGPso= github.com/nishanths/predeclared v0.2.1/go.mod h1:HvkGJcA3naj4lOwnFXFDkFxVtSqQMB9sbB1usJ+xjQE= github.com/nishanths/predeclared v0.2.2 h1:V2EPdZPliZymNAn79T8RkNApBjMmVKh5XRpLm/w98Vk= @@ -1115,22 +1047,17 @@ github.com/nishanths/predeclared v0.2.2/go.mod h1:RROzoN6TnGQupbC+lqggsOlcgysk3L github.com/nunnatsa/ginkgolinter v0.16.2 h1:8iLqHIZvN4fTLDC0Ke9tbSZVcyVHoBs0HIbnVSxfHJk= github.com/nunnatsa/ginkgolinter v0.16.2/go.mod h1:4tWRinDN1FeJgU+iJANW/kz7xKN5nYRAOfJDQUS9dOQ= github.com/nxadm/tail v1.4.4/go.mod h1:kenIhsEOeOJmVchQTgglprH7qJGnHDVpk1VPCcaMI8A= -github.com/nxadm/tail v1.4.8/go.mod h1:+ncqLTQzXmGhMZNUePPaPqPvBxHAIsmXswZKocGu+AU= github.com/oklog/oklog v0.3.2/go.mod h1:FCV+B7mhrz4o+ueLpx+KqkyXRGMWOYEvfiXtdGtbWGs= github.com/oklog/run v1.0.0/go.mod h1:dlhp/R75TPv97u0XWUtDeV/lRKWPKSdTuV0TZvrmrQA= github.com/oklog/ulid v1.3.1/go.mod h1:CirwcVhetQ6Lv90oh/F+FBtV6XMibvdAFo93nm5qn4U= github.com/olekukonko/tablewriter v0.0.0-20170122224234-a0225b3f23b5/go.mod h1:vsDQFd/mU46D+Z4whnwzcISnGGzXWMclvtLoiIKAKIo= -github.com/olekukonko/tablewriter v0.0.1/go.mod h1:vsDQFd/mU46D+Z4whnwzcISnGGzXWMclvtLoiIKAKIo= -github.com/olekukonko/tablewriter v0.0.2/go.mod h1:rSAaSIOAGT9odnlyGlUfAJaoc5w2fSBUmeGDbRWPxyQ= github.com/olekukonko/tablewriter v0.0.4/go.mod h1:zq6QwlOf5SlnkVbMSr5EoBv3636FWnp+qbPhuoO21uA= github.com/olekukonko/tablewriter v0.0.5 h1:P2Ga83D34wi1o9J6Wh1mRuqd4mF/x/lgBS7N7AbDhec= github.com/olekukonko/tablewriter v0.0.5/go.mod h1:hPp6KlRPjbx+hW8ykQs1w3UBbZlj6HuIJcUGPhkA7kY= github.com/onsi/ginkgo v1.6.0/go.mod h1:lLunBs/Ym6LB5Z9jYTR76FiuTmxDTDusOGeTQH+WWjE= github.com/onsi/ginkgo v1.7.0/go.mod h1:lLunBs/Ym6LB5Z9jYTR76FiuTmxDTDusOGeTQH+WWjE= -github.com/onsi/ginkgo v1.10.3/go.mod h1:lLunBs/Ym6LB5Z9jYTR76FiuTmxDTDusOGeTQH+WWjE= github.com/onsi/ginkgo v1.12.1/go.mod h1:zj2OWP4+oCPe1qIXoGWkgMRwljMUYCdkwsT2108oapk= github.com/onsi/ginkgo v1.14.2/go.mod h1:iSB4RoI2tjJc9BBv4NKIKWKya62Rps+oPG/Lv9klQyY= -github.com/onsi/ginkgo v1.15.0/go.mod h1:hF8qUzuuC8DJGygJH3726JnCZX4MYbRB8yFfISqnKUg= github.com/onsi/ginkgo v1.16.5 h1:8xi0RTUf59SOSfEtZMvwTvXYMzG4gV23XVHOZiXNtnE= github.com/onsi/ginkgo/v2 v2.20.2 h1:7NVCeyIWROIAheY21RLS+3j2bb52W0W82tkberYytp4= github.com/onsi/ginkgo/v2 v2.20.2/go.mod h1:K9gyxPIlb+aIvnZ8bd9Ak+YP18w3APlR+5coaZoE2ag= @@ -1138,7 +1065,6 @@ github.com/onsi/gomega v1.4.3/go.mod h1:ex+gbHU/CVuBBDIJjb2X0qEXbFg53c61hWP/1Cpa github.com/onsi/gomega v1.7.1/go.mod h1:XdKZgCCFLUoM/7CFJVPcG8C1xQ1AJ0vpAezJrB7JYyY= github.com/onsi/gomega v1.10.1/go.mod h1:iN09h71vgCQne3DLsj+A5owkum+a2tYe+TOCB1ybHNo= github.com/onsi/gomega v1.10.4/go.mod h1:g/HbgYopi++010VEqkFgJHKC09uJiW9UkXvMUuKHUCQ= -github.com/onsi/gomega v1.10.5/go.mod h1:gza4q3jKQJijlu05nKWRCW/GavJumGt8aNRxWg7mt48= github.com/onsi/gomega v1.34.2 h1:pNCwDkzrsv7MS9kpaQvVb1aVLahQXyJ/Tv5oAZMI3i8= github.com/onsi/gomega v1.34.2/go.mod h1:v1xfxRgk0KIsG+QOdm7p8UosrOzPYRo60fd3B/1Dukc= github.com/op/go-logging v0.0.0-20160315200505-970db520ece7/go.mod h1:HzydrMdWErDVzsI23lYNej1Htcns9BCg93Dk0bBINWk= @@ -1171,7 +1097,6 @@ github.com/pelletier/go-toml v1.9.5/go.mod h1:u1nR/EPcESfeI/szUZKdtJ0xRNbUoANCko github.com/pelletier/go-toml/v2 v2.2.3 h1:YmeHyLY8mFWbdkNWwpr+qIL2bEqT0o95WSdkNHvL12M= github.com/pelletier/go-toml/v2 v2.2.3/go.mod h1:MfCQTFTvCcUyyvvwm1+G6H/jORL20Xlb6rzQu9GuUkc= github.com/performancecopilot/speed v3.0.0+incompatible/go.mod h1:/CLtqpZ5gBg1M9iaPbIdPPGyKcA8hKdoy6hAWba7Yac= -github.com/peterbourgon/diskv v2.0.1+incompatible/go.mod h1:uqqh8zWWbv1HBMNONnaR/tNboyR3/BZd58JJSHlUSCU= github.com/phayes/checkstyle v0.0.0-20170904204023-bfd46e6a821d/go.mod h1:3OzsM7FXDQlpCiw2j81fOmAwQLnZnLGXVKUzeKQXIAw= github.com/phpdave11/gofpdf v1.4.2/go.mod h1:zpO6xFn9yxo3YLyMvW8HcKWVdbNqgIfOOp2dXMnm1mY= github.com/phpdave11/gofpdi v1.0.12/go.mod h1:vBmVV0Do6hSBHC8uKUQ71JGW+ZGQq74llk/7bXwjDoI= @@ -1238,7 +1163,6 @@ github.com/pkg/profile v1.7.0/go.mod h1:8Uer0jas47ZQMJ7VD+OHknK4YDY07LPUC6dEvqDj github.com/pkg/sftp v1.10.1/go.mod h1:lYOWFsE0bwd1+KfKJaKeuokY15vzFx25BLbzYYoAxZI= github.com/planetscale/vtprotobuf v0.6.1-0.20240319094008-0393e58bdf10 h1:GFCKgmp0tecUJ0sJuv4pzYCqS9+RGSn52M3FUwPs+uo= github.com/planetscale/vtprotobuf v0.6.1-0.20240319094008-0393e58bdf10/go.mod h1:t/avpk3KcrXxUnYOhZhMXJlSEyie6gQbtLq5NM3loB8= -github.com/pmezard/go-difflib v0.0.0-20151028094244-d8ed2627bdf0/go.mod h1:iKH77koFhYxTK1pcRnkKkqfTogsbg7gZNVY4sRDYZ/4= github.com/pmezard/go-difflib v1.0.0 h1:4DBwDE0NGyQoBHbLQYPwSUPoCMWR5BEzIk/f1lZbAQM= github.com/pmezard/go-difflib v1.0.0/go.mod h1:iKH77koFhYxTK1pcRnkKkqfTogsbg7gZNVY4sRDYZ/4= github.com/polyfloyd/go-errorlint v0.0.0-20201127212506-19bd8db6546f/go.mod h1:wi9BfjxjF/bwiZ701TzmfKu6UKC357IOAtNr0Td0Lvw= @@ -1287,23 +1211,15 @@ github.com/prometheus/procfs v0.6.0/go.mod h1:cz+aTbrPOrUb4q7XlbU9ygM+/jj0fzG6c1 github.com/prometheus/procfs v0.7.3 h1:4jVXhlkAyzOScmCkXBTOLRLTz8EeU+eyjrwB/EPq0VU= github.com/prometheus/procfs v0.7.3/go.mod h1:cz+aTbrPOrUb4q7XlbU9ygM+/jj0fzG6c1xBZuNvfVA= github.com/prometheus/tsdb v0.7.1/go.mod h1:qhTCs0VvXwvX/y3TZrWD7rabWM+ijKTux40TwIPHuXU= -github.com/pseudomuto/protoc-gen-doc v1.3.2/go.mod h1:y5+P6n3iGrbKG+9O04V5ld71in3v/bX88wUwgt+U8EA= -github.com/pseudomuto/protokit v0.2.0/go.mod h1:2PdH30hxVHsup8KpBTOXTBeMVhJZVio3Q8ViKSAXT0Q= github.com/quasilyte/go-consistent v0.0.0-20190521200055-c6f3937de18c/go.mod h1:5STLWrekHfjyYwxBRVRXNOSewLJ3PWfDJd1VyTS21fI= github.com/quasilyte/go-ruleguard v0.3.0/go.mod h1:p2miAhLp6fERzFNbcuQ4bevXs8rgK//uCHsUDkumITg= -github.com/quasilyte/go-ruleguard v0.3.1-0.20210203134552-1b5a410e1cc8/go.mod h1:KsAh3x0e7Fkpgs+Q9pNLS5XpFSvYCEVl5gP9Pp1xp30= -github.com/quasilyte/go-ruleguard v0.3.1/go.mod h1:s41wdpioTcgelE3dlTUgK57UaUxjihg/DBGUccoN5IU= github.com/quasilyte/go-ruleguard v0.4.3-0.20240823090925-0fe6f58b47b1 h1:+Wl/0aFp0hpuHM3H//KMft64WQ1yX9LdJY64Qm/gFCo= github.com/quasilyte/go-ruleguard v0.4.3-0.20240823090925-0fe6f58b47b1/go.mod h1:GJLgqsLeo4qgavUoL8JeGFNS7qcisx3awV/w9eWTmNI= github.com/quasilyte/go-ruleguard/dsl v0.0.0-20210106184943-e47d54850b18/go.mod h1:KeCP03KrjuSO0H1kTuZQCWlQPulDV6YMIXmpQss17rU= github.com/quasilyte/go-ruleguard/dsl v0.0.0-20210115110123-c73ee1cbff1f/go.mod h1:KeCP03KrjuSO0H1kTuZQCWlQPulDV6YMIXmpQss17rU= -github.com/quasilyte/go-ruleguard/dsl v0.3.0/go.mod h1:KeCP03KrjuSO0H1kTuZQCWlQPulDV6YMIXmpQss17rU= -github.com/quasilyte/go-ruleguard/dsl v0.3.1/go.mod h1:KeCP03KrjuSO0H1kTuZQCWlQPulDV6YMIXmpQss17rU= github.com/quasilyte/go-ruleguard/dsl v0.3.22 h1:wd8zkOhSNr+I+8Qeciml08ivDt1pSXe60+5DqOpCjPE= github.com/quasilyte/go-ruleguard/dsl v0.3.22/go.mod h1:KeCP03KrjuSO0H1kTuZQCWlQPulDV6YMIXmpQss17rU= github.com/quasilyte/go-ruleguard/rules v0.0.0-20201231183845-9e62ed36efe1/go.mod h1:7JTjp89EGyU1d6XfBiXihJNG37wB2VRkd125Q1u7Plc= -github.com/quasilyte/go-ruleguard/rules v0.0.0-20210203162857-b223e0831f88/go.mod h1:4cgAphtvu7Ftv7vOT2ZOYhC6CvBxZixcasr8qIOTA50= -github.com/quasilyte/go-ruleguard/rules v0.0.0-20210221215616-dfcc94e3dffd/go.mod h1:4cgAphtvu7Ftv7vOT2ZOYhC6CvBxZixcasr8qIOTA50= github.com/quasilyte/gogrep v0.5.0 h1:eTKODPXbI8ffJMN+W2aE0+oL0z/nh8/5eNdiO34SOAo= github.com/quasilyte/gogrep v0.5.0/go.mod h1:Cm9lpz9NZjEoL1tgZ2OgeUKPIxL1meE7eo60Z6Sk+Ng= github.com/quasilyte/regex/syntax v0.0.0-20200407221936-30656e2c4a95/go.mod h1:rlzQ04UMyJXu/aOvhd8qT+hvDrFpiwqp8MRXDY9szc0= @@ -1328,7 +1244,6 @@ github.com/rogpeppe/go-internal v1.12.0/go.mod h1:E+RYuTGaKKdloAfM02xzb0FW3Paa99 github.com/rs/cors v1.7.0/go.mod h1:gFx+x8UowdsKA9AchylcLynDq+nNFfI8FkUZdN/jGCU= github.com/rs/cors v1.11.1 h1:eU3gRzXLRK57F5rKMGMZURNdIG4EoAmX8k94r9wXWHA= github.com/rs/cors v1.11.1/go.mod h1:XyqrcTp5zjWr1wsJ8PIRZssZ8b/WMcMf71DJnit4EMU= -github.com/russross/blackfriday v1.5.2/go.mod h1:JO/DiYxRf+HjHt06OyowR9PTA263kcR/rfWxYHBV53g= github.com/russross/blackfriday/v2 v2.0.1/go.mod h1:+Rmxgy9KzJVeS9/2gXHxylqXiyQDYRxCVz55jmeOWTM= github.com/russross/blackfriday/v2 v2.1.0 h1:JIOH55/0cWyOuilr9/qlrm0BSXldqnqwMsf35Ld67mk= github.com/russross/blackfriday/v2 v2.1.0/go.mod h1:+Rmxgy9KzJVeS9/2gXHxylqXiyQDYRxCVz55jmeOWTM= @@ -1343,7 +1258,6 @@ github.com/ryanrolds/sqlclosecheck v0.5.1/go.mod h1:2g3dUjoS6AL4huFdv6wn55WpLIDj github.com/ryanuber/columnize v0.0.0-20160712163229-9b3edd62028f/go.mod h1:sm1tb6uqfes/u+d4ooFouqFdy9/2g9QGwK3SQygK0Ts= github.com/samuel/go-zookeeper v0.0.0-20190923202752-2cc03de413da/go.mod h1:gi+0XIa01GRL2eRQVjQkKGqKF3SF9vZR/HnPullcV2E= github.com/sanposhiho/wastedassign v0.1.3/go.mod h1:LGpq5Hsv74QaqM47WtIsRSF/ik9kqk07kchgv66tLVE= -github.com/sanposhiho/wastedassign v0.2.0/go.mod h1:LGpq5Hsv74QaqM47WtIsRSF/ik9kqk07kchgv66tLVE= github.com/sanposhiho/wastedassign/v2 v2.0.7 h1:J+6nrY4VW+gC9xFzUc+XjPD3g3wF3je/NsJFwFK7Uxc= github.com/sanposhiho/wastedassign/v2 v2.0.7/go.mod h1:KyZ0MWTwxxBmfwn33zh3k1dmsbF2ud9pAAGfoLfjhtI= github.com/santhosh-tekuri/jsonschema/v5 v5.3.1 h1:lZUw3E0/J3roVtGQ+SCrUrg3ON6NgVqpn3+iol9aGu4= @@ -1354,16 +1268,13 @@ github.com/sashamelentyev/usestdlibvars v1.27.0 h1:t/3jZpSXtRPRf2xr0m63i32Zrusyu github.com/sashamelentyev/usestdlibvars v1.27.0/go.mod h1:9nl0jgOfHKWNFS43Ojw0i7aRoS4j6EBye3YBhmAIRF8= github.com/sean-/seed v0.0.0-20170313163322-e2103e2c3529/go.mod h1:DxrIzT+xaE7yg65j358z/aeFdxmN0P9QXhEzd20vsDc= github.com/securego/gosec/v2 v2.6.1/go.mod h1:I76p3NTHBXsGhybUW+cEQ692q2Vp+A0Z6ZLzDIZy+Ao= -github.com/securego/gosec/v2 v2.7.0/go.mod h1:xNbGArrGUspJLuz3LS5XCY1EBW/0vABAl/LWfSklmiM= github.com/securego/gosec/v2 v2.21.2 h1:deZp5zmYf3TWwU7A7cR2+SolbTpZ3HQiwFqnzQyEl3M= github.com/securego/gosec/v2 v2.21.2/go.mod h1:au33kg78rNseF5PwPnTWhuYBFf534bvJRvOrgZ/bFzU= -github.com/sergi/go-diff v1.1.0/go.mod h1:STckp+ISIX8hZLjrqAeVduY0gWCT9IjLuqbuNXdaHfM= github.com/sergi/go-diff v1.3.1 h1:xkr+Oxo4BOQKmkn/B9eMK0g5Kg/983T9DqqPHwYqD+8= github.com/sergi/go-diff v1.3.1/go.mod h1:aMJSSKb2lpPvRNec0+w3fl7LP9IOFzdc9Pa4NFbPK1I= github.com/shazow/go-diff v0.0.0-20160112020656-b6b7b6733b8c h1:W65qqJCIOVP4jpqPQ0YvHYKwcMEMVWIzWC5iNQQfBTU= github.com/shazow/go-diff v0.0.0-20160112020656-b6b7b6733b8c/go.mod h1:/PevMnwAxekIXwN8qQyfc5gl2NlkB3CQlkizAbOkeBs= github.com/shirou/gopsutil/v3 v3.21.1/go.mod h1:igHnfak0qnw1biGeI2qKQvu0ZkwvEkUcCLlYhZzdr/4= -github.com/shirou/gopsutil/v3 v3.21.2/go.mod h1:ghfMypLDrFSWN2c9cDYFLHyynQ+QUht0cv/18ZqVczw= github.com/shurcooL/go v0.0.0-20180423040247-9e1955d9fb6e/go.mod h1:TDJrrUr11Vxrven61rcy3hJMUqaf/CLWYhHNPmT14Lk= github.com/shurcooL/go-goon v0.0.0-20170922171312-37c2f522c041/go.mod h1:N5mDOmsrJOB+vfqUK+7DmDyjhSLIIBnXo9lvZJj3MWQ= github.com/shurcooL/sanitized_anchor_name v1.0.0/go.mod h1:1NzhyTcUVG4SuEtjjoZeVRXNmyL/1OwPU0+IJeTBvfc= @@ -1372,7 +1283,6 @@ github.com/sirupsen/logrus v1.4.2/go.mod h1:tLMulIdttU9McNUspp0xgXVQah82FyeX6Mwd github.com/sirupsen/logrus v1.6.0/go.mod h1:7uNnSEd1DgxDLC74fIahvMZmmYsHGZGEOFrfsX/uA88= github.com/sirupsen/logrus v1.7.0/go.mod h1:yWOB1SBYBC5VeMP7gHvWumXLIWorT60ONWic61uBYv0= github.com/sirupsen/logrus v1.8.0/go.mod h1:4GuYW9TZmE769R5STWrRakJc4UqQ3+QQ95fyz7ENv1A= -github.com/sirupsen/logrus v1.8.1/go.mod h1:yWOB1SBYBC5VeMP7gHvWumXLIWorT60ONWic61uBYv0= github.com/sirupsen/logrus v1.9.0/go.mod h1:naHLuLoDiP4jHNo9R0sCBMtWGeIprob74mVsIT4qYEQ= github.com/sirupsen/logrus v1.9.3 h1:dueUQJ1C2q9oE3F7wvmSGAaVtTmUizReu6fjN8uqzbQ= github.com/sirupsen/logrus v1.9.3/go.mod h1:naHLuLoDiP4jHNo9R0sCBMtWGeIprob74mVsIT4qYEQ= @@ -1381,9 +1291,6 @@ github.com/sivchari/containedctx v1.0.3/go.mod h1:c1RDvCbnJLtH4lLcYD/GqwiBSSf4F5 github.com/sivchari/tenv v1.10.0 h1:g/hzMA+dBCKqGXgW8AV/1xIWhAvDrx0zFKNR48NFMg0= github.com/sivchari/tenv v1.10.0/go.mod h1:tdY24masnVoZFxYrHv/nD6Tc8FbkEtAQEEziXpyMgqY= github.com/smartystreets/assertions v0.0.0-20180927180507-b2de0cb4f26d/go.mod h1:OnSkiWE9lh6wB0YB77sQom3nweQdgAjqCqsofrRNTgc= -github.com/smartystreets/assertions v1.2.0/go.mod h1:tcbTF8ujkAEcZ8TElKY+i30BzYlVhC/LOxJk7iOWnoo= -github.com/smartystreets/assertions v1.13.0 h1:Dx1kYM01xsSqKPno3aqLnrwac2LetPvN23diwyr69Qs= -github.com/smartystreets/assertions v1.13.0/go.mod h1:wDmR7qL282YbGsPy6H/yAsesrxfxaaSlJazyFLYVFx8= github.com/smartystreets/goconvey v1.6.4/go.mod h1:syvi0/a8iFYH4r/RixwvyeAJjdLS9QV7WQ/tjFTllLA= github.com/soheilhy/cmux v0.1.4/go.mod h1:IM3LyeVVIOuxMH7sFAkER9+bJ4dT7Ms6E4xg4kGIyLM= github.com/sonatard/noctx v0.0.1/go.mod h1:9D2D/EoULe8Yy2joDHJj7bv3sZoq9AaSb8B4lqBjiZI= @@ -1404,7 +1311,6 @@ github.com/spf13/cast v1.3.0/go.mod h1:Qx5cxh0v+4UWYiBimWS+eyWzqEqokIECu5etghLkU github.com/spf13/cast v1.5.0 h1:rj3WzYc11XZaIZMPKmwP96zkFEnnAmV8s6XbB2aY32w= github.com/spf13/cast v1.5.0/go.mod h1:SpXXQ5YoyJw6s3/6cMTQuxvgRl3PCJiyaX9p6b155UU= github.com/spf13/cobra v0.0.3/go.mod h1:1l0Ry5zgKvJasoi3XT1TypsSe7PqH0Sj9dhYf7v3XqQ= -github.com/spf13/cobra v0.0.5/go.mod h1:3K3wKZymM7VvHMDS9+Akkh4K60UwM26emMESw8tLCHU= github.com/spf13/cobra v1.1.3/go.mod h1:pGADOWyqRD/YMrPZigI/zbliZ2wVD/23d+is3pSWzOo= github.com/spf13/cobra v1.8.1 h1:e5/vxKd/rZsfSJMUX1agtjeTDf+qv1/JdBF8gg5k9ZM= github.com/spf13/cobra v1.8.1/go.mod h1:wHxEcudfqmLYa8iTfL+OuZPbBZkmvliBWKIezN3kD9Y= @@ -1415,7 +1321,6 @@ github.com/spf13/pflag v1.0.1/go.mod h1:DYY7MBk1bdzusC3SYhjObp+wFpr4gzcvqqNjLnIn github.com/spf13/pflag v1.0.3/go.mod h1:DYY7MBk1bdzusC3SYhjObp+wFpr4gzcvqqNjLnInEg4= github.com/spf13/pflag v1.0.5 h1:iy+VFUOCP1a+8yFto/drg2CJ5u0yRoB7fZw3DKv/JXA= github.com/spf13/pflag v1.0.5/go.mod h1:McXfInJRrz4CZXVZOBLb0bTZqETkiAhM9Iw0y3An2Bg= -github.com/spf13/viper v1.3.2/go.mod h1:ZiWeW+zYFKm7srdB9IoDzzZXaJaI5eL9QjNiN/DMA2s= github.com/spf13/viper v1.7.0/go.mod h1:8WkrPz2fc9jxqZNCJI/76HCieCp4Q8HaLFoCha5qpdg= github.com/spf13/viper v1.7.1/go.mod h1:8WkrPz2fc9jxqZNCJI/76HCieCp4Q8HaLFoCha5qpdg= github.com/spf13/viper v1.12.0 h1:CZ7eSOd3kZoaYDLbXnmzgQI5RlciuXBMA+18HwHRfZQ= @@ -1436,7 +1341,6 @@ github.com/stretchr/objx v0.4.0/go.mod h1:YvHI0jy2hoMjB+UWwv71VJQ9isScKT/TqJzVSS github.com/stretchr/objx v0.5.0/go.mod h1:Yh+to48EsGEfYuaHDzXPcE3xhTkx73EhmCGUpEOglKo= github.com/stretchr/objx v0.5.2 h1:xuMeJ0Sdp5ZMRXx/aWO6RZxdr3beISkG5/G/aIRr3pY= github.com/stretchr/objx v0.5.2/go.mod h1:FRsXN1f5AsAjCGJKqEizvkpNtU+EGNCLh3NxZ/8L+MA= -github.com/stretchr/testify v0.0.0-20170130113145-4d4bfba8f1d1/go.mod h1:a8OnRcib4nhh0OaRAV+Yts87kKdq0PP7pXfy6kDkUVs= github.com/stretchr/testify v1.1.4/go.mod h1:a8OnRcib4nhh0OaRAV+Yts87kKdq0PP7pXfy6kDkUVs= github.com/stretchr/testify v1.2.0/go.mod h1:a8OnRcib4nhh0OaRAV+Yts87kKdq0PP7pXfy6kDkUVs= github.com/stretchr/testify v1.2.2/go.mod h1:a8OnRcib4nhh0OaRAV+Yts87kKdq0PP7pXfy6kDkUVs= @@ -1477,16 +1381,11 @@ github.com/timakin/bodyclose v0.0.0-20230421092635-574207250966 h1:quvGphlmUVU+n github.com/timakin/bodyclose v0.0.0-20230421092635-574207250966/go.mod h1:27bSVNWSBOHm+qRp1T9qzaIpsWEP6TbUnei/43HK+PQ= github.com/timonwong/loggercheck v0.9.4 h1:HKKhqrjcVj8sxL7K77beXh0adEm6DLjV/QOGeMXEVi4= github.com/timonwong/loggercheck v0.9.4/go.mod h1:caz4zlPcgvpEkXgVnAJGowHAMW2NwHaNlpS8xDbVhTg= -github.com/tklauser/go-sysconf v0.3.4/go.mod h1:Cl2c8ZRWfHD5IrfHo9VN+FX9kCFjIOyVklgXycLB6ek= -github.com/tklauser/numcpus v0.2.1/go.mod h1:9aU+wOc6WjUIZEwWMP62PL/41d65P+iks1gBkr4QyP8= github.com/tmc/grpc-websocket-proxy v0.0.0-20170815181823-89b8d40f7ca8/go.mod h1:ncp9v5uamzpCO7NfCPTXjqaC+bZgJeR0sMTm6dMHP7U= github.com/tmc/grpc-websocket-proxy v0.0.0-20190109142713-0ad062ec5ee5/go.mod h1:ncp9v5uamzpCO7NfCPTXjqaC+bZgJeR0sMTm6dMHP7U= -github.com/tmc/grpc-websocket-proxy v0.0.0-20200427203606-3cfed13b9966/go.mod h1:ncp9v5uamzpCO7NfCPTXjqaC+bZgJeR0sMTm6dMHP7U= github.com/tomarrell/wrapcheck v0.0.0-20201130113247-1683564d9756/go.mod h1:yiFB6fFoV7saXirUGfuK+cPtUh4NX/Hf5y2WC2lehu0= -github.com/tomarrell/wrapcheck v1.0.0/go.mod h1:Bd3i1FaEKe3XmcPoHhNQ+HM0S8P6eIXoQIoGj/ndJkU= github.com/tomarrell/wrapcheck/v2 v2.9.0 h1:801U2YCAjLhdN8zhZ/7tdjB3EnAoRlJHt/s+9hijLQ4= github.com/tomarrell/wrapcheck/v2 v2.9.0/go.mod h1:g9vNIyhb5/9TQgumxQyOEqDHsmGYcGsVMOx/xGkqdMo= -github.com/tomasen/realip v0.0.0-20180522021738-f0c99a92ddce/go.mod h1:o8v6yHRoik09Xen7gje4m9ERNah1d1PPsVq1VEx9vE4= github.com/tommy-muehle/go-mnd/v2 v2.3.1/go.mod h1:WsUAkMJMYww6l/ufffCD3m+P7LEvr8TnZn9lwVDlgzw= github.com/tommy-muehle/go-mnd/v2 v2.5.1 h1:NowYhSdyE/1zwK9QCLeRb6USWdoif80Ie+v+yU8u1Zw= github.com/tommy-muehle/go-mnd/v2 v2.5.1/go.mod h1:WsUAkMJMYww6l/ufffCD3m+P7LEvr8TnZn9lwVDlgzw= @@ -1498,7 +1397,6 @@ github.com/u2takey/go-utils v0.3.1 h1:TaQTgmEZZeDHQFYfd+AdUT1cT4QJgJn/XVPELhHw4y github.com/u2takey/go-utils v0.3.1/go.mod h1:6e+v5vEZ/6gu12w/DC2ixZdZtCrNokVxD0JUklcqdCs= github.com/ugorji/go v1.1.7 h1:/68gy2h+1mWMrwZFeD1kQialdSzAb432dtpeJ42ovdo= github.com/ugorji/go v1.1.7/go.mod h1:kZn38zHttfInRq0xu/PH0az30d+z6vm202qpg1oXVMw= -github.com/ugorji/go/codec v0.0.0-20181204163529-d75b2dcb6bc8/go.mod h1:VFNgLljTbGfSG7qAOspJ7OScBnGdDN/yBr0sguwnwf0= github.com/ugorji/go/codec v1.1.7/go.mod h1:Ax+UKWsSmolVDwsd+7N3ZtXu+yMGCf907BLYF3GoBXY= github.com/ugorji/go/codec v1.2.11 h1:BMaWp1Bb6fHwEtbplGBGJ498wD+LKlNSl25MjdZY4dU= github.com/ugorji/go/codec v1.2.11/go.mod h1:UNopzCgEMSXjBc6AOMqYvWC1ktqTAfzJZUZgYf6w6lg= @@ -1526,7 +1424,6 @@ github.com/viamrobotics/evdev v0.1.3 h1:mR4HFafvbc5Wx4Vp1AUJp6/aITfVx9AKyXWx+rWj github.com/viamrobotics/evdev v0.1.3/go.mod h1:N6nuZmPz7HEIpM7esNWwLxbYzqWqLSZkfI/1Sccckqk= github.com/viamrobotics/webrtc/v3 v3.99.10 h1:ykE14wm+HkqMD5Ozq4rvhzzfvnXAu14ak/HzA1OCzfY= github.com/viamrobotics/webrtc/v3 v3.99.10/go.mod h1:ziH7/S52IyYAeDdwUUl5ZTbuyKe47fWorAz+0z5w6NA= -github.com/viki-org/dnscache v0.0.0-20130720023526-c70c1f23c5d8/go.mod h1:dniwbG03GafCjFohMDmz6Zc6oCuiqgH6tGNyXTkHzXE= github.com/wcharczuk/go-chart/v2 v2.1.0/go.mod h1:yx7MvAVNcP/kN9lKXM/NTce4au4DFN99j6i1OwDclNA= github.com/wlynxg/anet v0.0.3 h1:PvR53psxFXstc12jelG6f1Lv4MWqE0tI76/hHGjh9rg= github.com/wlynxg/anet v0.0.3/go.mod h1:eay5PRQr7fIVAMbTbchTnO9gG65Hg/uYGdc7mguHxoA= @@ -1543,7 +1440,6 @@ github.com/xen0n/gosmopolitan v1.2.2/go.mod h1:7XX7Mj61uLYrj0qmeN0zi7XDon9JRAEhY github.com/xfmoulet/qoi v0.2.0 h1:+Smrwzy5ptRnPzGm/YHkZfyK9qGUSoOpiEPngGmFv+c= github.com/xfmoulet/qoi v0.2.0/go.mod h1:uuPUygmV7o8qy7PhiaGAQX0iLiqoUvFEUKjwUFtlaTQ= github.com/xiang90/probing v0.0.0-20190116061207-43a291ad63a2/go.mod h1:UETIi67q53MR2AWcXfiuqkDkRtnGDLqkBTpCHuJHxtU= -github.com/xordataexchange/crypt v0.0.3-0.20170626215501-b2862e3d0a77/go.mod h1:aYKd//L2LvnjZzWKhF00oedf4jCCReLcmhLdhm1A27Q= github.com/xrash/smetrics v0.0.0-20201216005158-039620a65673 h1:bAn7/zixMGCfxrRTfdpNzjtPYqr8smhKouy9mxVdGPU= github.com/xrash/smetrics v0.0.0-20201216005158-039620a65673/go.mod h1:N3UwUGtsrSj3ccvlPHLoLsHnpR27oXr4ZE984MbSER8= github.com/xtgo/set v1.0.0 h1:6BCNBRv3ORNDQ7fyoJXRv+tstJz3m1JVFQErfeZz2pY= @@ -1557,9 +1453,6 @@ github.com/ykadowak/zerologlint v0.1.5/go.mod h1:KaUskqF3e/v59oPmdq1U1DnKcuHokl2 github.com/youmark/pkcs8 v0.0.0-20181117223130-1be2e3e5546d/go.mod h1:rHwXgn7JulP+udvsHwJoVG1YGAP6VLg4y9I5dyZdqmA= github.com/youmark/pkcs8 v0.0.0-20201027041543-1326539a0a0a h1:fZHgsYlfvtyqToslyjUt3VOPF4J7aK/3MPcK7xp3PDk= github.com/youmark/pkcs8 v0.0.0-20201027041543-1326539a0a0a/go.mod h1:ul22v+Nro/R083muKhosV54bj5niojjWZvU8xrevuH4= -github.com/yudai/gojsondiff v1.0.0/go.mod h1:AY32+k2cwILAkW1fbgxQ5mUmMiZFgLIV+FBNExI05xg= -github.com/yudai/golcs v0.0.0-20170316035057-ecda9a501e82/go.mod h1:lgjkn3NuSvDfVJdfcVVdX+jpBxNmX4rDAzaS45IcYoM= -github.com/yudai/pp v2.0.1+incompatible/go.mod h1:PuxR/8QJ7cyCkFp/aUDS+JY727OFEZkTdatxwunjIkc= github.com/yuin/goldmark v1.1.25/go.mod h1:3hX8gzYuyVAZsxl0MRgGTJEmQBFcNTphYh9decYSb74= github.com/yuin/goldmark v1.1.27/go.mod h1:3hX8gzYuyVAZsxl0MRgGTJEmQBFcNTphYh9decYSb74= github.com/yuin/goldmark v1.1.32/go.mod h1:3hX8gzYuyVAZsxl0MRgGTJEmQBFcNTphYh9decYSb74= @@ -1583,12 +1476,9 @@ go-simpler.org/sloglint v0.7.2 h1:Wc9Em/Zeuu7JYpl+oKoYOsQSy2X560aVueCW/m6IijY= go-simpler.org/sloglint v0.7.2/go.mod h1:US+9C80ppl7VsThQclkM7BkCHQAzuz8kHLsW3ppuluo= go.etcd.io/bbolt v1.3.2/go.mod h1:IbVyRI1SCnLcuJnV2u8VeU0CEYM7e686BmAb1XKL+uU= go.etcd.io/bbolt v1.3.3/go.mod h1:IbVyRI1SCnLcuJnV2u8VeU0CEYM7e686BmAb1XKL+uU= -go.etcd.io/bbolt v1.3.4/go.mod h1:G5EMThwa9y8QZGBClrRx5EY+Yw9kAhnjy3bSjsnlVTQ= go.etcd.io/etcd v0.0.0-20191023171146-3cf2f69b5738/go.mod h1:dnLIgRNXwCJa5e+c6mIZCrds/GIG4ncV9HhK5PX7jPg= -go.etcd.io/etcd v0.0.0-20200513171258-e048e166ab9c/go.mod h1:xCI7ZzBfRuGgBXyXO6yfWfDmlWd35khcWpUa4L0xI/k= go.mongodb.org/mongo-driver v1.11.6 h1:XM7G6PjiGAO5betLF13BIa5TlLUUE3uJ/2Ox3Lz1K+o= go.mongodb.org/mongo-driver v1.11.6/go.mod h1:G9TgswdsWjX4tmDA5zfs2+6AEPpYJwqblyjsfuh8oXY= -go.mozilla.org/mozlog v0.0.0-20170222151521-4bb13139d403/go.mod h1:jHoPAGnDrCy6kaI2tAze5Prf0Nr0w/oNkROt2lw3n3o= go.opencensus.io v0.20.1/go.mod h1:6WKK9ahsWS3RSO+PY9ZHZUfv2irvY6gN279GOPZjmmk= go.opencensus.io v0.20.2/go.mod h1:6WKK9ahsWS3RSO+PY9ZHZUfv2irvY6gN279GOPZjmmk= go.opencensus.io v0.21.0/go.mod h1:mSImk1erAIZhrmZN+AvHh14ztQfjbGwt4TtuofqLduU= @@ -1625,7 +1515,6 @@ go.uber.org/goleak v1.3.0 h1:2K3zAYmnTNqV73imy9J1T3WC+gmCePx2hEGkimedGto= go.uber.org/goleak v1.3.0/go.mod h1:CoHD4mav9JJNrW/WLlf7HGZPjdw8EucARQHekz1X6bE= go.uber.org/multierr v1.1.0/go.mod h1:wR5kodmAFQ0UK8QlbwjlSNy0Z68gJhDJUG5sjR94q/0= go.uber.org/multierr v1.3.0/go.mod h1:VgVr7evmIr6uPjLBxg28wmKNXyqE9akIJ5XnfpiKl+4= -go.uber.org/multierr v1.4.0/go.mod h1:VgVr7evmIr6uPjLBxg28wmKNXyqE9akIJ5XnfpiKl+4= go.uber.org/multierr v1.6.0/go.mod h1:cdWPpRnG4AhwMwsgIHip0KRBQjJy5kYEpYjJxpXp9iU= go.uber.org/multierr v1.11.0 h1:blXXJkSxSSfBVBlC76pxqeO+LN3aDfLQo+309xJstO0= go.uber.org/multierr v1.11.0/go.mod h1:20+QtiLqy0Nd6FdQB9TLXag12DsQkrbs3htMFfDN80Y= @@ -1639,8 +1528,8 @@ go.uber.org/zap v1.27.0 h1:aJMhYGrd5QSmlpLMr2MftRKl7t8J8PTZPA732ud/XR8= go.uber.org/zap v1.27.0/go.mod h1:GB2qFLM7cTU87MWRP2mPIjqfIDnGu+VIO4V/SdhGo2E= go.viam.com/api v0.1.357 h1:L9LBYbaH0imv/B+mVxqtSgClIl4flzjLV6LclfnD9Nc= go.viam.com/api v0.1.357/go.mod h1:5lpVRxMsKFCaahqsnJfPGwJ9baoQ6PIKQu3lxvy6Wtw= -go.viam.com/test v1.1.1-0.20220913152726-5da9916c08a2 h1:oBiK580EnEIzgFLU4lHOXmGAE3MxnVbeR7s1wp/F3Ps= -go.viam.com/test v1.1.1-0.20220913152726-5da9916c08a2/go.mod h1:XM0tej6riszsiNLT16uoyq1YjuYPWlRBweTPRDanIts= +go.viam.com/test v1.2.3 h1:tT2QqthC2BL2tiloUC2T1AIwuLILyMRx8mmxunN+cT4= +go.viam.com/test v1.2.3/go.mod h1:5pXMnEyvTygilOCaFtonnKNMqsCCBbe2ZXU8ZsJ2zjY= go.viam.com/utils v0.1.112 h1:yuVkNITUijdP/CMI3BaDozUMZwP4Ari57BvRQfORFK0= go.viam.com/utils v0.1.112/go.mod h1:SYvcY/TKy9yv1d95era4IEehImkXffWu/5diDBS/4X4= go4.org/unsafe/assume-no-moving-gc v0.0.0-20230525183740-e7c30c78aeb2 h1:WJhcL4p+YeDxmZWg141nRm7XC8IDmhz7lk5GpadO1Sg= @@ -1650,10 +1539,8 @@ goji.io v2.0.2+incompatible h1:uIssv/elbKRLznFUy3Xj4+2Mz/qKhek/9aZQDUMae7c= goji.io v2.0.2+incompatible/go.mod h1:sbqFwrtqZACxLBTQcdgVjFh54yGVCvwq8+w49MVMMIk= golang.org/x/arch v0.3.0 h1:02VY4/ZcO/gBOH6PUaoiptASxtXU10jazRCP865E97k= golang.org/x/arch v0.3.0/go.mod h1:5om86z9Hs0C8fWVUuoMHwpExlXzs5Tkyp9hOrfG7pp8= -golang.org/x/crypto v0.0.0-20180501155221-613d6eafa307/go.mod h1:6SG95UA2DQfeDnfUPMdvaQW0Q7yPrPDi9nlGo2tz2b4= golang.org/x/crypto v0.0.0-20180904163835-0709b304e793/go.mod h1:6SG95UA2DQfeDnfUPMdvaQW0Q7yPrPDi9nlGo2tz2b4= golang.org/x/crypto v0.0.0-20181029021203-45a5f77698d3/go.mod h1:6SG95UA2DQfeDnfUPMdvaQW0Q7yPrPDi9nlGo2tz2b4= -golang.org/x/crypto v0.0.0-20181203042331-505ab145d0a9/go.mod h1:6SG95UA2DQfeDnfUPMdvaQW0Q7yPrPDi9nlGo2tz2b4= golang.org/x/crypto v0.0.0-20190308221718-c2843e01d9a2/go.mod h1:djNgcEr1/C05ACkg1iLfiJU5Ep61QUkGW8qpdssI0+w= golang.org/x/crypto v0.0.0-20190510104115-cbcb75029529/go.mod h1:yigFU9vqHzYiE8UmvKecakEJjdnWj3jj499lnFckfCI= golang.org/x/crypto v0.0.0-20190605123033-f99c8df09eb5/go.mod h1:yigFU9vqHzYiE8UmvKecakEJjdnWj3jj499lnFckfCI= @@ -1662,8 +1549,6 @@ golang.org/x/crypto v0.0.0-20190820162420-60c769a6c586/go.mod h1:yigFU9vqHzYiE8U golang.org/x/crypto v0.0.0-20191011191535-87dc89f01550/go.mod h1:yigFU9vqHzYiE8UmvKecakEJjdnWj3jj499lnFckfCI= golang.org/x/crypto v0.0.0-20200302210943-78000ba7a073/go.mod h1:LzIPMQfyMNhhGPhUkYOs5KpL4U8rLKemX1yGLhDgUto= golang.org/x/crypto v0.0.0-20200622213623-75b288015ac9/go.mod h1:LzIPMQfyMNhhGPhUkYOs5KpL4U8rLKemX1yGLhDgUto= -golang.org/x/crypto v0.0.0-20201221181555-eec23a3978ad/go.mod h1:jdWPYTVW3xRLrWPugEBEK3UY2ZEsg3UU495nc5E+M+I= -golang.org/x/crypto v0.0.0-20210220033148-5ea612d1eb83/go.mod h1:jdWPYTVW3xRLrWPugEBEK3UY2ZEsg3UU495nc5E+M+I= golang.org/x/crypto v0.0.0-20210921155107-089bfa567519/go.mod h1:GvvjBRRGRdwPK5ydBHafDWAxML/pGHZbMvKqRZ5+Abc= golang.org/x/crypto v0.0.0-20220622213112-05595931fe9d/go.mod h1:IxCIyHEi3zRg3s0A5j5BB6A9Jmi73HwBIUl50j+osU4= golang.org/x/crypto v0.1.0/go.mod h1:RecgLatLF4+eUMCP1PoPZQb+cVrJcOPbHkTkbkB9sbw= @@ -1753,7 +1638,6 @@ golang.org/x/net v0.0.0-20190628185345-da137c7871d7/go.mod h1:z5CRVTTTmAJ677TzLL golang.org/x/net v0.0.0-20190724013045-ca1201d0de80/go.mod h1:z5CRVTTTmAJ677TzLLGU+0bjPO0LkuOLi4/5GtJWs/s= golang.org/x/net v0.0.0-20190813141303-74dc4d7220e7/go.mod h1:z5CRVTTTmAJ677TzLLGU+0bjPO0LkuOLi4/5GtJWs/s= golang.org/x/net v0.0.0-20190923162816-aa69164e4478/go.mod h1:z5CRVTTTmAJ677TzLLGU+0bjPO0LkuOLi4/5GtJWs/s= -golang.org/x/net v0.0.0-20191002035440-2ec189313ef0/go.mod h1:z5CRVTTTmAJ677TzLLGU+0bjPO0LkuOLi4/5GtJWs/s= golang.org/x/net v0.0.0-20191209160850-c0dbc17a3553/go.mod h1:z5CRVTTTmAJ677TzLLGU+0bjPO0LkuOLi4/5GtJWs/s= golang.org/x/net v0.0.0-20200114155413-6afb5195e5aa/go.mod h1:z5CRVTTTmAJ677TzLLGU+0bjPO0LkuOLi4/5GtJWs/s= golang.org/x/net v0.0.0-20200202094626-16171245cfb2/go.mod h1:z5CRVTTTmAJ677TzLLGU+0bjPO0LkuOLi4/5GtJWs/s= @@ -1809,7 +1693,6 @@ golang.org/x/sync v0.0.0-20180314180146-1d60e4601c6f/go.mod h1:RxMgew5VJxzue5/jJ golang.org/x/sync v0.0.0-20181108010431-42b317875d0f/go.mod h1:RxMgew5VJxzue5/jJTE5uejpjVlOe/izrB70Jof72aM= golang.org/x/sync v0.0.0-20181221193216-37e7f081c4d4/go.mod h1:RxMgew5VJxzue5/jJTE5uejpjVlOe/izrB70Jof72aM= golang.org/x/sync v0.0.0-20190227155943-e225da77a7e6/go.mod h1:RxMgew5VJxzue5/jJTE5uejpjVlOe/izrB70Jof72aM= -golang.org/x/sync v0.0.0-20190412183630-56d357773e84/go.mod h1:RxMgew5VJxzue5/jJTE5uejpjVlOe/izrB70Jof72aM= golang.org/x/sync v0.0.0-20190423024810-112230192c58/go.mod h1:RxMgew5VJxzue5/jJTE5uejpjVlOe/izrB70Jof72aM= golang.org/x/sync v0.0.0-20190911185100-cd5d95a43a6e/go.mod h1:RxMgew5VJxzue5/jJTE5uejpjVlOe/izrB70Jof72aM= golang.org/x/sync v0.0.0-20200317015054-43a5402ce75a/go.mod h1:RxMgew5VJxzue5/jJTE5uejpjVlOe/izrB70Jof72aM= @@ -1830,7 +1713,6 @@ golang.org/x/sys v0.0.0-20181026203630-95b1ffbd15a5/go.mod h1:STP8DvDyc/dI5b8T5h golang.org/x/sys v0.0.0-20181107165924-66b7b1311ac8/go.mod h1:STP8DvDyc/dI5b8T5hshtkjS+E42TnysNCUPdjciGhY= golang.org/x/sys v0.0.0-20181116152217-5ac8a444bdc5/go.mod h1:STP8DvDyc/dI5b8T5hshtkjS+E42TnysNCUPdjciGhY= golang.org/x/sys v0.0.0-20181122145206-62eef0e2fa9b/go.mod h1:STP8DvDyc/dI5b8T5hshtkjS+E42TnysNCUPdjciGhY= -golang.org/x/sys v0.0.0-20181205085412-a5c9d58dba9a/go.mod h1:STP8DvDyc/dI5b8T5hshtkjS+E42TnysNCUPdjciGhY= golang.org/x/sys v0.0.0-20190215142949-d0b11bdaac8a/go.mod h1:STP8DvDyc/dI5b8T5hshtkjS+E42TnysNCUPdjciGhY= golang.org/x/sys v0.0.0-20190222072716-a9d3bda3a223/go.mod h1:STP8DvDyc/dI5b8T5hshtkjS+E42TnysNCUPdjciGhY= golang.org/x/sys v0.0.0-20190312061237-fead79001313/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= @@ -1844,10 +1726,8 @@ golang.org/x/sys v0.0.0-20190726091711-fc99dfbffb4e/go.mod h1:h1NjWce9XRLGQEsW7w golang.org/x/sys v0.0.0-20190826190057-c7b8b68b1456/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20190904154756-749cb33beabd/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20190913121621-c3b328c6e5a7/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= -golang.org/x/sys v0.0.0-20190924154521-2837fb4f24fe/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20191001151750-bb3f8db39f24/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20191005200804-aed5e4c7ecf9/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= -golang.org/x/sys v0.0.0-20191008105621-543471e840be/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20191026070338-33540a1f6037/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20191120155948-bd437916bb0e/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20191204072324-ce4227a45e2e/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= @@ -1877,11 +1757,8 @@ golang.org/x/sys v0.0.0-20200909081042-eff7692f9009/go.mod h1:h1NjWce9XRLGQEsW7w golang.org/x/sys v0.0.0-20200930185726-fdedc70b468f/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20201024232916-9f70ab9862d5/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20201119102817-f84b799fce68/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= -golang.org/x/sys v0.0.0-20210112080510-489259a85091/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20210119212857-b64e53b001e4/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20210124154548-22da62e12c0c/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= -golang.org/x/sys v0.0.0-20210217105451-b926d437f341/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= -golang.org/x/sys v0.0.0-20210228012217-479acdf4ea46/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20210303074136-134d130e1a04/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20210330210617-4fbd30eecc44/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= golang.org/x/sys v0.0.0-20210423082822-04245dca01da/go.mod h1:h1NjWce9XRLGQEsW7wpKNCjG9DtNlClVuFLEZdDNbEs= @@ -1920,7 +1797,6 @@ golang.org/x/sys v0.17.0/go.mod h1:/VUhepiaJMQUp4+oa/7Zr1D23ma6VTLIYjOOTFZPUcA= golang.org/x/sys v0.18.0/go.mod h1:/VUhepiaJMQUp4+oa/7Zr1D23ma6VTLIYjOOTFZPUcA= golang.org/x/sys v0.26.0 h1:KHjCJyddX0LoSTb3J+vWpupP9p0oznkqVk/IfjymZbo= golang.org/x/sys v0.26.0/go.mod h1:/VUhepiaJMQUp4+oa/7Zr1D23ma6VTLIYjOOTFZPUcA= -golang.org/x/term v0.0.0-20201117132131-f5c789dd3221/go.mod h1:Nr5EML6q2oocZ2LXRh80K7BxOlk5/8JxuGnuhpl+muw= golang.org/x/term v0.0.0-20201126162022-7de9c90e9dd1/go.mod h1:bj7SfCRtBDWHUb9snDiAeCFNEtKQo2Wmx5Cou7ajbmo= golang.org/x/term v0.0.0-20210927222741-03fcf44c2211/go.mod h1:jbD1KX2456YbFQfuXm/mYQcufACuNUgVhRMnK/tPxf8= golang.org/x/term v0.0.0-20220526004731-065cf7ba2467/go.mod h1:jbD1KX2456YbFQfuXm/mYQcufACuNUgVhRMnK/tPxf8= @@ -1957,7 +1833,6 @@ golang.org/x/time v0.0.0-20180412165947-fbb02b2291d2/go.mod h1:tRJNPiyCQ0inRvYxb golang.org/x/time v0.0.0-20181108054448-85acf8d2951c/go.mod h1:tRJNPiyCQ0inRvYxbN9jk5I+vvW/OXSQhTDSoE431IQ= golang.org/x/time v0.0.0-20190308202827-9d24e82272b4/go.mod h1:tRJNPiyCQ0inRvYxbN9jk5I+vvW/OXSQhTDSoE431IQ= golang.org/x/time v0.0.0-20191024005414-555d28b269f0/go.mod h1:tRJNPiyCQ0inRvYxbN9jk5I+vvW/OXSQhTDSoE431IQ= -golang.org/x/time v0.0.0-20200416051211-89c76fbcd5d1/go.mod h1:tRJNPiyCQ0inRvYxbN9jk5I+vvW/OXSQhTDSoE431IQ= golang.org/x/time v0.6.0 h1:eTDhh4ZXt5Qf0augr54TN6suAUudPcawVZeIAPU7D4U= golang.org/x/time v0.6.0/go.mod h1:3BpzKBy/shNhVucY/MWOyx10tF3SFh9QdLuxbVysPQM= golang.org/x/tools v0.0.0-20180221164845-07fd8470d635/go.mod h1:n7NCudcB/nEzxVGmLbDWY5pfWTLqBcC2KZ6jyYvM4mQ= @@ -2000,7 +1875,6 @@ golang.org/x/tools v0.0.0-20191115202509-3a792d9c32b2/go.mod h1:b+2E5dAYhXwXZwtn golang.org/x/tools v0.0.0-20191119224855-298f0cb1881e/go.mod h1:b+2E5dAYhXwXZwtnZ6UAqBI28+e2cm9otk0dWdXHAEo= golang.org/x/tools v0.0.0-20191125144606-a911d9008d1f/go.mod h1:b+2E5dAYhXwXZwtnZ6UAqBI28+e2cm9otk0dWdXHAEo= golang.org/x/tools v0.0.0-20191130070609-6e064ea0cf2d/go.mod h1:b+2E5dAYhXwXZwtnZ6UAqBI28+e2cm9otk0dWdXHAEo= -golang.org/x/tools v0.0.0-20191216052735-49a3e744a425/go.mod h1:TB2adYChydJhpapKDTa4BR/hXlZSLoq2Wpct/0txZ28= golang.org/x/tools v0.0.0-20191216173652-a0e659d51361/go.mod h1:TB2adYChydJhpapKDTa4BR/hXlZSLoq2Wpct/0txZ28= golang.org/x/tools v0.0.0-20191227053925-7b8e75db28f4/go.mod h1:TB2adYChydJhpapKDTa4BR/hXlZSLoq2Wpct/0txZ28= golang.org/x/tools v0.0.0-20200103221440-774c71fcf114/go.mod h1:TB2adYChydJhpapKDTa4BR/hXlZSLoq2Wpct/0txZ28= @@ -2020,7 +1894,6 @@ golang.org/x/tools v0.0.0-20200329025819-fd4102a86c65/go.mod h1:Sl4aGygMT6LrqrWc golang.org/x/tools v0.0.0-20200331025713-a30bf2db82d4/go.mod h1:Sl4aGygMT6LrqrWclx+PTx3U+LnKx/seiNR+3G19Ar8= golang.org/x/tools v0.0.0-20200414032229-332987a829c3/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= golang.org/x/tools v0.0.0-20200422022333-3d57cf2e726e/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= -golang.org/x/tools v0.0.0-20200426102838-f3a5411a4c3b/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= golang.org/x/tools v0.0.0-20200501065659-ab2804fb9c9d/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= golang.org/x/tools v0.0.0-20200512131952-2bc93b1c0c88/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= golang.org/x/tools v0.0.0-20200515010526-7d3b6ebf133d/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= @@ -2030,9 +1903,6 @@ golang.org/x/tools v0.0.0-20200619180055-7c47624df98f/go.mod h1:EkVYQZoAsY45+roY golang.org/x/tools v0.0.0-20200622203043-20e05c1c8ffa/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= golang.org/x/tools v0.0.0-20200624225443-88f3c62a19ff/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= golang.org/x/tools v0.0.0-20200625211823-6506e20df31f/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= -golang.org/x/tools v0.0.0-20200626171337-aa94e735be7f/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= -golang.org/x/tools v0.0.0-20200630154851-b2d8b0336632/go.mod h1:EkVYQZoAsY45+roYkvgYkIh4xh/qjgUK9TdY2XT94GE= -golang.org/x/tools v0.0.0-20200706234117-b22de6825cf7/go.mod h1:njjCfa9FT2d7l9Bc6FUM5FLjQPp3cFF28FI3qnDFljA= golang.org/x/tools v0.0.0-20200717024301-6ddee64345a6/go.mod h1:njjCfa9FT2d7l9Bc6FUM5FLjQPp3cFF28FI3qnDFljA= golang.org/x/tools v0.0.0-20200724022722-7017fd6b1305/go.mod h1:njjCfa9FT2d7l9Bc6FUM5FLjQPp3cFF28FI3qnDFljA= golang.org/x/tools v0.0.0-20200729194436-6467de6f59a7/go.mod h1:njjCfa9FT2d7l9Bc6FUM5FLjQPp3cFF28FI3qnDFljA= @@ -2048,7 +1918,6 @@ golang.org/x/tools v0.0.0-20201023174141-c8cfbd0f21e6/go.mod h1:emZCQorbCU4vsT4f golang.org/x/tools v0.0.0-20201028025901-8cd080b735b3/go.mod h1:emZCQorbCU4vsT4fOWvOPXz4eW1wZW4PmDk9uLelYpA= golang.org/x/tools v0.0.0-20201114224030-61ea331ec02b/go.mod h1:emZCQorbCU4vsT4fOWvOPXz4eW1wZW4PmDk9uLelYpA= golang.org/x/tools v0.0.0-20201118003311-bd56c0adb394/go.mod h1:emZCQorbCU4vsT4fOWvOPXz4eW1wZW4PmDk9uLelYpA= -golang.org/x/tools v0.0.0-20201224043029-2b0845dc783e/go.mod h1:emZCQorbCU4vsT4fOWvOPXz4eW1wZW4PmDk9uLelYpA= golang.org/x/tools v0.0.0-20201230224404-63754364767c/go.mod h1:emZCQorbCU4vsT4fOWvOPXz4eW1wZW4PmDk9uLelYpA= golang.org/x/tools v0.0.0-20210101214203-2dba1e4ea05c/go.mod h1:emZCQorbCU4vsT4fOWvOPXz4eW1wZW4PmDk9uLelYpA= golang.org/x/tools v0.0.0-20210102185154-773b96fafca2/go.mod h1:emZCQorbCU4vsT4fOWvOPXz4eW1wZW4PmDk9uLelYpA= @@ -2107,9 +1976,7 @@ google.golang.org/appengine v1.6.1/go.mod h1:i06prIuMbXzDqacNJfV5OdTW448YApPu5ww google.golang.org/appengine v1.6.2/go.mod h1:i06prIuMbXzDqacNJfV5OdTW448YApPu5ww/cMBSeb0= google.golang.org/appengine v1.6.5/go.mod h1:8WjMMxjGQR8xUklV/ARdw2HLXBOI7O7uCIDZVag1xfc= google.golang.org/appengine v1.6.6/go.mod h1:8WjMMxjGQR8xUklV/ARdw2HLXBOI7O7uCIDZVag1xfc= -google.golang.org/genproto v0.0.0-20170818010345-ee236bd376b0/go.mod h1:JiN7NxoALGmiZfu7CAH4rXhgtRTLTxftemlI0sWmxmc= google.golang.org/genproto v0.0.0-20180817151627-c66870c02cf8/go.mod h1:JiN7NxoALGmiZfu7CAH4rXhgtRTLTxftemlI0sWmxmc= -google.golang.org/genproto v0.0.0-20181107211654-5fc9ac540362/go.mod h1:JiN7NxoALGmiZfu7CAH4rXhgtRTLTxftemlI0sWmxmc= google.golang.org/genproto v0.0.0-20190307195333-5fe7a883aa19/go.mod h1:VzzqZJRnGkLBvHegQrXjBqPurQTc5/KpmUdxsrq26oE= google.golang.org/genproto v0.0.0-20190418145605-e7d98fc518a7/go.mod h1:VzzqZJRnGkLBvHegQrXjBqPurQTc5/KpmUdxsrq26oE= google.golang.org/genproto v0.0.0-20190425155659-357c62f0e4bb/go.mod h1:VzzqZJRnGkLBvHegQrXjBqPurQTc5/KpmUdxsrq26oE= @@ -2118,7 +1985,6 @@ google.golang.org/genproto v0.0.0-20190530194941-fb225487d101/go.mod h1:z3L6/3dT google.golang.org/genproto v0.0.0-20190801165951-fa694d86fc64/go.mod h1:DMBHOl98Agz4BDEuKkezgsaosCRResVns1a3J2ZsMNc= google.golang.org/genproto v0.0.0-20190819201941-24fa4b261c55/go.mod h1:DMBHOl98Agz4BDEuKkezgsaosCRResVns1a3J2ZsMNc= google.golang.org/genproto v0.0.0-20190911173649-1774047e7e51/go.mod h1:IbNlFCBrqXvoKpeg0TB2l7cyZUmoaFKYIwrEpbDKLA8= -google.golang.org/genproto v0.0.0-20190927181202-20e1ac93f88c/go.mod h1:IbNlFCBrqXvoKpeg0TB2l7cyZUmoaFKYIwrEpbDKLA8= google.golang.org/genproto v0.0.0-20191108220845-16a3f7862a1a/go.mod h1:n3cpQtvxv34hfy77yVDNjmbRyujviMdxYliBSkLhpCc= google.golang.org/genproto v0.0.0-20191115194625-c23dd37a84c9/go.mod h1:n3cpQtvxv34hfy77yVDNjmbRyujviMdxYliBSkLhpCc= google.golang.org/genproto v0.0.0-20191216164720-4f79533eabd1/go.mod h1:n3cpQtvxv34hfy77yVDNjmbRyujviMdxYliBSkLhpCc= @@ -2139,8 +2005,6 @@ google.golang.org/genproto v0.0.0-20200513103714-09dca8ec2884/go.mod h1:55QSHmfG google.golang.org/genproto v0.0.0-20200515170657-fc4c6c6a6587/go.mod h1:YsZOwe1myG/8QRHRsmBRE1LrgQY60beZKjly0O1fX9U= google.golang.org/genproto v0.0.0-20200526211855-cb27e3aa2013/go.mod h1:NbSheEEYHJ7i3ixzK3sjbqSGDJWnxyFXZblF3eUsNvo= google.golang.org/genproto v0.0.0-20200618031413-b414f8b61790/go.mod h1:jDfRM7FcilCzHH/e9qn6dsT145K34l5v+OpcnNgKAAA= -google.golang.org/genproto v0.0.0-20200626011028-ee7919e894b5/go.mod h1:FWY/as6DDZQgahTzZj3fqbO1CbirC29ZNUFHwi0/+no= -google.golang.org/genproto v0.0.0-20200707001353-8e8330bf89df/go.mod h1:FWY/as6DDZQgahTzZj3fqbO1CbirC29ZNUFHwi0/+no= google.golang.org/genproto v0.0.0-20200729003335-053ba62fc06f/go.mod h1:FWY/as6DDZQgahTzZj3fqbO1CbirC29ZNUFHwi0/+no= google.golang.org/genproto v0.0.0-20200804131852-c06518451d9c/go.mod h1:FWY/as6DDZQgahTzZj3fqbO1CbirC29ZNUFHwi0/+no= google.golang.org/genproto v0.0.0-20200825200019-8632dd797987/go.mod h1:FWY/as6DDZQgahTzZj3fqbO1CbirC29ZNUFHwi0/+no= @@ -2152,7 +2016,6 @@ google.golang.org/genproto/googleapis/api v0.0.0-20240827150818-7e3bb234dfed h1: google.golang.org/genproto/googleapis/api v0.0.0-20240827150818-7e3bb234dfed/go.mod h1:OCdP9MfskevB/rbYvHTsXTtKC+3bHWajPdoKgjcYkfo= google.golang.org/genproto/googleapis/rpc v0.0.0-20240903143218-8af14fe29dc1 h1:pPJltXNxVzT4pK9yD8vR9X75DaWYYmLGMsEvBfFQZzQ= google.golang.org/genproto/googleapis/rpc v0.0.0-20240903143218-8af14fe29dc1/go.mod h1:UqMtugtsSgubUsoxbuAoiCXvqvErP7Gf0so0mK9tHxU= -google.golang.org/grpc v1.8.0/go.mod h1:yo6s7OP7yaDglbqo1J04qKzAhqBH6lvTonzMVmEdcZw= google.golang.org/grpc v1.17.0/go.mod h1:6QZJwpn2B+Zp71q/5VxRsJ6NXXVCE5NRUHRo+f3cWCs= google.golang.org/grpc v1.19.0/go.mod h1:mqu4LbDTu4XGKhr4mRzUsmM4RtVoemTSY81AxZiDr8c= google.golang.org/grpc v1.20.0/go.mod h1:chYK+tFQF0nDUGJgXMSgLCQk3phJEuONr2DCgLDdAQM= @@ -2162,13 +2025,11 @@ google.golang.org/grpc v1.21.1/go.mod h1:oYelfM1adQP15Ek0mdvEgi9Df8B9CZIaU1084ij google.golang.org/grpc v1.22.1/go.mod h1:Y5yQAOtifL1yxbo5wqy6BxZv8vAUGQwXBOALyacEbxg= google.golang.org/grpc v1.23.0/go.mod h1:Y5yQAOtifL1yxbo5wqy6BxZv8vAUGQwXBOALyacEbxg= google.golang.org/grpc v1.23.1/go.mod h1:Y5yQAOtifL1yxbo5wqy6BxZv8vAUGQwXBOALyacEbxg= -google.golang.org/grpc v1.24.0/go.mod h1:XDChyiUovWa60DnaeDeZmSW86xtLtjtZbwvSiRnRtcA= google.golang.org/grpc v1.25.1/go.mod h1:c3i+UQWmh7LiEpx4sFZnkU36qjEYZ0imhYfXVyQciAY= google.golang.org/grpc v1.26.0/go.mod h1:qbnxyOmOxrQa7FizSgH+ReBfzJrCY1pSN7KXBS8abTk= google.golang.org/grpc v1.27.0/go.mod h1:qbnxyOmOxrQa7FizSgH+ReBfzJrCY1pSN7KXBS8abTk= google.golang.org/grpc v1.27.1/go.mod h1:qbnxyOmOxrQa7FizSgH+ReBfzJrCY1pSN7KXBS8abTk= google.golang.org/grpc v1.28.0/go.mod h1:rpkK4SK4GF4Ach/+MFLZUBavHOvF2JJB5uozKKal+60= -google.golang.org/grpc v1.29.0/go.mod h1:itym6AZVZYACWQqET3MqgPpjcuV5QH3BxFS3IjizoKk= google.golang.org/grpc v1.29.1/go.mod h1:itym6AZVZYACWQqET3MqgPpjcuV5QH3BxFS3IjizoKk= google.golang.org/grpc v1.30.0/go.mod h1:N36X2cJ7JwdamYAgDz+s+rVMFjt3numwzf/HckM8pak= google.golang.org/grpc v1.31.0/go.mod h1:N36X2cJ7JwdamYAgDz+s+rVMFjt3numwzf/HckM8pak= @@ -2207,7 +2068,6 @@ gopkg.in/check.v1 v1.0.0-20200902074654-038fdea0a05b/go.mod h1:Co6ibVJAznAaIkqp8 gopkg.in/check.v1 v1.0.0-20201130134442-10cb98267c6c h1:Hei/4ADfdWqJk1ZMxUNpqntNwaWcugrBjAiHlqqRiVk= gopkg.in/check.v1 v1.0.0-20201130134442-10cb98267c6c/go.mod h1:JHkPIbrfpd72SG/EVd6muEfDQjcINNoR0C8j2r3qZ4Q= gopkg.in/cheggaaa/pb.v1 v1.0.25/go.mod h1:V/YB90LKu/1FcN3WVnfiiE5oMCibMjukxqG/qStrOgw= -gopkg.in/cheggaaa/pb.v1 v1.0.28/go.mod h1:V/YB90LKu/1FcN3WVnfiiE5oMCibMjukxqG/qStrOgw= gopkg.in/errgo.v2 v2.1.0/go.mod h1:hNsd1EY+bozCKY1Ytp96fpM3vjJbqLJn88ws8XvfDNI= gopkg.in/fsnotify.v1 v1.4.7/go.mod h1:Tz8NjZHkW78fSQdbUxIjBTcgA1z1m8ZHf0WmKUhAMys= gopkg.in/gcfg.v1 v1.2.3/go.mod h1:yesOnuUOFQAhST5vPY4nbZsb/huCgGGXlipJsBn0b3o= @@ -2228,7 +2088,6 @@ gopkg.in/yaml.v2 v2.2.2/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= gopkg.in/yaml.v2 v2.2.3/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= gopkg.in/yaml.v2 v2.2.4/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= gopkg.in/yaml.v2 v2.2.5/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= -gopkg.in/yaml.v2 v2.2.6/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= gopkg.in/yaml.v2 v2.2.7/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= gopkg.in/yaml.v2 v2.2.8/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= gopkg.in/yaml.v2 v2.3.0/go.mod h1:hI93XBmqTisBFMUTm0b8Fm+jr3Dg1NNxqwp+5A1VGuI= @@ -2263,7 +2122,6 @@ honnef.co/go/tools v0.5.1/go.mod h1:e9irvo83WDG9/irijV44wr3tbhcFeRnfpVlRqVwpzMs= howett.net/plist v1.0.0 h1:7CrbWYbPPO/PyNy38b2EB/+gYbjCe2DXBxgtOOZbSQM= howett.net/plist v1.0.0/go.mod h1:lqaXoTrLY4hg8tnEzNru53gicrbv7rrk+2xJA/7hw9g= mvdan.cc/gofumpt v0.1.0/go.mod h1:yXG1r1WqZVKWbVRtBWKWX9+CxGYfA51nSomhM0woR48= -mvdan.cc/gofumpt v0.1.1/go.mod h1:yXG1r1WqZVKWbVRtBWKWX9+CxGYfA51nSomhM0woR48= mvdan.cc/gofumpt v0.7.0 h1:bg91ttqXmi9y2xawvkuMXyvAA/1ZGJqYAEGjXuP0JXU= mvdan.cc/gofumpt v0.7.0/go.mod h1:txVFJy/Sc/mvaycET54pV8SW8gWxTlUuGHVEcncmNUo= mvdan.cc/interfacer v0.0.0-20180901003855-c20040233aed/go.mod h1:Xkxe497xwlCKkIaQYRfC7CSLworTXY9RMqwhhCm+8Nc= From b4e1960e6963080cd6723843a592ac260ff079c9 Mon Sep 17 00:00:00 2001 From: Dan Gottlieb Date: Wed, 6 Nov 2024 16:04:03 -0500 Subject: [PATCH 28/51] RSDK-8819: Implement FTDC file rotation. (#4510) --- ftdc/ftdc.go | 113 ++++++++++++++++++++++++++++++++++++--------- ftdc/ftdc_test.go | 115 ++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 207 insertions(+), 21 deletions(-) diff --git a/ftdc/ftdc.go b/ftdc/ftdc.go index 62278ae3d85..9be785c21dc 100644 --- a/ftdc/ftdc.go +++ b/ftdc/ftdc.go @@ -1,12 +1,12 @@ package ftdc import ( - "bytes" "context" "errors" "fmt" "io" "os" + "path" "slices" "sync" "time" @@ -104,14 +104,16 @@ type FTDC struct { outputWorkerDone chan struct{} // Fields used to manage where serialized FTDC bytes are written. - // - // When debug is true, the `outputWriter` will "tee" data to both the `currOutputFile` and - // `inmemBuffer`. Otherwise `outputWriter` will just refer to the `currOutputFile`. - debug bool - outputWriter io.Writer - currOutputFile *os.File - // inmemBuffer will remain nil when `debug` is false. - inmemBuffer *bytes.Buffer + outputWriter io.Writer + // bytesWrittenCounter will count bytes that are written to the `outputWriter`. We use an + // `io.Writer` implementer for this, as opposed to just counting by hand, primarily as a + // convenience for working with `json.NewEncoder(writer).Encode(...)`. This counter is folded + // into the above `outputWriter`. + bytesWrittenCounter countingWriter + currOutputFile *os.File + maxFileSizeBytes int64 + // ftdcDir controls where FTDC data files will be written. + ftdcDir string logger logging.Logger } @@ -129,6 +131,7 @@ func NewWithWriter(writer io.Writer, logger logging.Logger) *FTDC { outputWorkerDone: make(chan struct{}), logger: logger, outputWriter: writer, + maxFileSizeBytes: 1_000_000, } } @@ -175,7 +178,8 @@ func (ftdc *FTDC) Remove(name string) { "name", name, "generationId", ftdc.inputGenerationID) } -// Start spins off the background goroutine for collecting/writing FTDC data. +// Start spins off the background goroutine for collecting + writing FTDC data. It's normal for tests +// to _not_ call `Start`. Tests can simulate the same functionality by calling `constructDatum` and `writeDatum`. func (ftdc *FTDC) Start() { ftdc.readStatsWorker = utils.NewStoppableWorkerWithTicker(time.Second, ftdc.statsReader) utils.PanicCapturingGo(ftdc.statsWriter) @@ -225,6 +229,7 @@ func (ftdc *FTDC) statsWriter() { return } + // FSync the ftdc data once every 30 iterations (roughly every 30 seconds). datumsWritten++ if datumsWritten%30 == 0 && ftdc.currOutputFile != nil { utils.UncheckedError(ftdc.currOutputFile.Sync()) @@ -233,7 +238,9 @@ func (ftdc *FTDC) statsWriter() { } // StopAndJoin stops the background worker started by `Start`. It is only legal to call this after -// `Start` returns. +// `Start` returns. It's normal for tests to _not_ call `StopAndJoin`. Tests that have spun up the +// `statsWriter` by hand, without the `statsReader` can `close(ftdc.datumCh)` followed by +// `<-ftdc.outputWorkerDone` to stop+wait for the `statsWriter`. func (ftdc *FTDC) StopAndJoin(ctx context.Context) { ftdc.readStatsWorker.Stop() close(ftdc.datumCh) @@ -354,25 +361,89 @@ func (ftdc *FTDC) writeDatum(datum datum) error { } // getWriter returns an io.Writer xor error for writing schema/data information. `getWriter` is only -// expected to be called by `newDatum`. +// expected to be called by `writeDatum`. func (ftdc *FTDC) getWriter() (io.Writer, error) { - if ftdc.outputWriter != nil { + // If we have an `outputWriter` without a `currOutputFile`, it means ftdc was constructed with + // an explicit writer. We will use the passed in writer for all operations. No file will ever be + // created. + if ftdc.outputWriter != nil && ftdc.currOutputFile == nil { return ftdc.outputWriter, nil } + // Note to readers, until this function starts mutating `outputWriter` and `currOutputFile`, you + // can safely assume: + // + // `outputWriter == nil if and only if currOutputFile == nil`. + // + // In case that helps reading the following logic. + + // If we have an active outputWriter and we have not exceeded our FTDC file rotation quota, we + // can just return. + if ftdc.outputWriter != nil && ftdc.bytesWrittenCounter.count < ftdc.maxFileSizeBytes { + return ftdc.outputWriter, nil + } + + // If we're in the logic branch where we have exceeded our FTDC file rotation quota, we first + // close the `currOutputFile`. + if ftdc.currOutputFile != nil { + // Dan: An error closing a file (any resource for that matter) is not an error. I will die + // on that hill. + utils.UncheckedError(ftdc.currOutputFile.Close()) + } + var err error - ftdc.currOutputFile, err = os.Create("./viam-server.ftdc") - if err != nil { + // It's unclear in what circumstance we'd expect creating a new file to fail. Try 5 times for no + // good reason before giving up entirely and shutting down FTDC. + for numTries := 0; numTries < 5; numTries++ { + now := time.Now().UTC() + // lint wants 0o600 file permissions. We don't expect the unix user someone is ssh'ed in as + // to be on the same unix user as is running the viam-server process. Thus the file needs to + // be accessible by anyone. + // + //nolint:gosec + ftdc.currOutputFile, err = os.OpenFile(path.Join(ftdc.ftdcDir, + // Filename example: viam-server-2024-10-04T18-42-02.ftdc + fmt.Sprintf("viam-server-%d-%02d-%02dT%02d-%02d-%02dZ.ftdc", + now.Year(), now.Month(), now.Day(), now.Hour(), now.Minute(), now.Second())), + // Create a new file in read+write mode. `O_EXCL` is used to guarantee a new file is + // created. If the filename already exists, that flag changes the `os.OpenFile` behavior + // to return an error. + os.O_RDWR|os.O_CREATE|os.O_EXCL, 0o644) + if err == nil { + break + } ftdc.logger.Warnw("FTDC failed to open file", "err", err) + + // If the error is some unexpected filename collision, wait a second to change the filename. + time.Sleep(time.Second) + } + if err != nil { return nil, err } - if ftdc.debug { - ftdc.inmemBuffer = bytes.NewBuffer(nil) - ftdc.outputWriter = io.MultiWriter(ftdc.currOutputFile, ftdc.inmemBuffer) - } else { - ftdc.outputWriter = ftdc.currOutputFile - } + // New file, reset the bytes written counter. + ftdc.bytesWrittenCounter.count = 0 + + // When we create a new file, we must rewrite the schema. If we do not, a file may be useless + // without its "ancestors". + // + // As a hack, we decrement the `outputGenerationID` to force a new schema to be written. + ftdc.outputGenerationID-- + + // Assign the `outputWriter`. The `outputWriter` is an abstraction for where FTDC formatted + // bytes go. Testing often prefers to just write bytes into memory (and consequently construct + // an FTDC with `NewWithWriter`). While in production we obviously want to persist bytes on + // disk. + ftdc.outputWriter = io.MultiWriter(&ftdc.bytesWrittenCounter, ftdc.currOutputFile) return ftdc.outputWriter, nil } + +type countingWriter struct { + count int64 +} + +func (cw *countingWriter) Write(p []byte) (int, error) { + cw.count += int64(len(p)) + return len(p), nil +} diff --git a/ftdc/ftdc_test.go b/ftdc/ftdc_test.go index 2d1ed698eb1..6ada0e76173 100644 --- a/ftdc/ftdc_test.go +++ b/ftdc/ftdc_test.go @@ -3,6 +3,10 @@ package ftdc import ( "bytes" "errors" + "io/fs" + "os" + "path/filepath" + "strings" "testing" "time" @@ -285,3 +289,114 @@ func TestStatsWriterContinuesOnSchemaError(t *testing.T) { // Wait for the `statsWriter` goroutine to exit. <-ftdc.outputWorkerDone } + +func TestCountingBytes(t *testing.T) { + logger := logging.NewTestLogger(t) + + // We must not use `NewWithWriter`. Forcing a writer for FTDC data is not compatible with FTDC + // file rotation. + ftdc := New(logger.Sublogger("ftdc")) + // Expect a log rotation after 1,000 bytes. For a changing `foo` object, this is ~60 datums. + ftdc.maxFileSizeBytes = 1000 + + ftdcFileDir, err := os.MkdirTemp("./", "countingBytesTest") + test.That(t, err, test.ShouldBeNil) + defer os.RemoveAll(ftdcFileDir) + + // Isolate all of the files we're going to create to a single, fresh directory. + ftdc.ftdcDir = ftdcFileDir + + timesRolledOver := 0 + foo := &foo{} + ftdc.Add("foo", foo) + for cnt := 0; cnt < 1000; cnt++ { + foo.x = cnt + foo.y = 2 * cnt + + datum := ftdc.constructDatum() + datum.Time = int64(cnt) + err := ftdc.writeDatum(datum) + test.That(t, err, test.ShouldBeNil) + + // If writing a datum takes the bytes written to larger than configured max file size, an + // explicit call to `getWriter` should create a new file and reset the count. + if ftdc.bytesWrittenCounter.count >= ftdc.maxFileSizeBytes { + // We're about to write a new ftdc file. The ftdc file names are a function of + // "now". Given the test runs fast, the generated name will collide (names only use + // seconds resolution). Make a subdirectory to avoid a naming conflict. + ftdc.ftdcDir, err = os.MkdirTemp(ftdcFileDir, "subdirectory") + test.That(t, err, test.ShouldBeNil) + + _, err = ftdc.getWriter() + test.That(t, err, test.ShouldBeNil) + test.That(t, ftdc.bytesWrittenCounter.count, test.ShouldBeLessThan, 1000) + timesRolledOver++ + } + } + logger.Info("Rolled over:", timesRolledOver) + + // Assert that the test rolled over at least once. Otherwise the test "passed" without + // exercising the intended code. + test.That(t, timesRolledOver, test.ShouldBeGreaterThan, 0) + + // We're about to walk all of the output FTDC files to make some assertions. Many assertions are + // isolated to within a single FTDC file, but the following two assertions are in aggregate + // across all of the files/data: + // - That the number of FTDC files found corresponds to the number of times we've "rolled over". + // - That every "time" in the [0, 1000) range we constructed a datum from is found. + numFTDCFiles := 0 + timeSeen := make(map[int64]struct{}) + filepath.Walk(ftdcFileDir, filepath.WalkFunc(func(path string, info fs.FileInfo, walkErr error) error { + logger.Info("Path:", path) + if !strings.HasSuffix(path, ".ftdc") { + return nil + } + + if walkErr != nil { + logger.Info("Unexpected walk error. Continuing under the assumption any actual* problem will", + "be caught by the assertions. WalkErr:", walkErr) + return nil + } + + // We have an FTDC file. Count it for a later test assertion. + numFTDCFiles++ + + // Additionally, parse the file (in isolation) and assert its contents are correct. + ftdcFile, err := os.Open(path) + test.That(t, err, test.ShouldBeNil) + defer ftdcFile.Close() + + // Temporarily set the log level to INFO to avoid spammy logs. Debug logs during parsing are + // only interesting when parsing fails. + logger.SetLevel(logging.INFO) + datums, err := ParseWithLogger(ftdcFile, logger) + logger.SetLevel(logging.DEBUG) + test.That(t, err, test.ShouldBeNil) + + for _, flatDatum := range datums { + // Each datum contains two metrics: `foo.X` and `foo.Y`. The "time" must be between [0, + // 1000). + test.That(t, flatDatum.Time, test.ShouldBeGreaterThanOrEqualTo, 0) + test.That(t, flatDatum.Time, test.ShouldBeLessThan, 1000) + + // Assert the "time" is new. + test.That(t, timeSeen, test.ShouldNotContainKey, flatDatum.Time) + // Mark the "time" as seen. + timeSeen[flatDatum.Time] = struct{}{} + + // As per construction: + // - `foo.X` must be equal to the "time" and + // - `foo.Y` must be `2*time`. + datum := flatDatum.asDatum() + test.That(t, datum.Data["foo"].(map[string]float32)["X"], test.ShouldEqual, flatDatum.Time) + test.That(t, datum.Data["foo"].(map[string]float32)["Y"], test.ShouldEqual, 2*flatDatum.Time) + } + + return nil + })) + test.That(t, len(timeSeen), test.ShouldEqual, 1000) + + // There will be 1 FTDC file per `timesRolledOver`. And an additional file for first call to + // `writeDatum`. Thus the subtraction of `1` to get the right equation. + test.That(t, timesRolledOver, test.ShouldEqual, numFTDCFiles-1) +} From fc6665dddb53ace2acf7ff6436b27d5948498cfe Mon Sep 17 00:00:00 2001 From: Ethan Look-Potts Date: Thu, 7 Nov 2024 17:31:39 -0500 Subject: [PATCH 29/51] APP-6785: Remove local control page - remove web workflows (#4523) --- .github/CODEOWNERS | 13 ------- .github/dependabot.yml | 11 ------ .github/workflows/full-static.yml | 2 -- .github/workflows/main.yml | 6 ---- .github/workflows/npm-bump-version.yml | 49 -------------------------- .github/workflows/npm-publish.yml | 33 ----------------- .github/workflows/releasecandidate.yml | 6 ---- .github/workflows/stable.yml | 6 ---- .github/workflows/test.yml | 38 +------------------- 9 files changed, 1 insertion(+), 163 deletions(-) delete mode 100644 .github/CODEOWNERS delete mode 100644 .github/workflows/npm-bump-version.yml delete mode 100644 .github/workflows/npm-publish.yml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS deleted file mode 100644 index 70c62d7186d..00000000000 --- a/.github/CODEOWNERS +++ /dev/null @@ -1,13 +0,0 @@ -# No code owners for all files -* - -# TODO(APP-5348): Remove code owners -# -# This code owners is to make sure that the Visualization team is aware -# of any changes that are going into RC while the team is updating -# the RC implementation in App. -# -# Code owners are no longer needed once RDK uses the shared, -# updated remote control cards from App. For any questions reach -# out to @ethanlook. -web/frontend @ethanlookpotts @micheal-parks @dtcurrie @zaporter-work diff --git a/.github/dependabot.yml b/.github/dependabot.yml index 5ce97f759eb..f8248f8c252 100644 --- a/.github/dependabot.yml +++ b/.github/dependabot.yml @@ -21,17 +21,6 @@ updates: assignees: #TODO: make list - stevebriskin - mcvella - - package-ecosystem: "npm" - directory: "web/frontend" - schedule: - interval: "daily" - allow: - - dependency-type: "all" - ignore: - - dependency-name: "proto" # generated proto files - - dependency-name: "*" - update-types: ["version-update:semver-major", "version-update:semver-minor", "version-update:semver-patch"] - open-pull-requests-limit: 0 - package-ecosystem: "github-actions" directory: "/" schedule: diff --git a/.github/workflows/full-static.yml b/.github/workflows/full-static.yml index 3afa947e299..514edc0e820 100644 --- a/.github/workflows/full-static.yml +++ b/.github/workflows/full-static.yml @@ -45,8 +45,6 @@ jobs: with: go-version-file: go.mod - - name: build js - run: make build-web - name: build go shell: bash run: | diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index aaf5052e11c..f7369a2d450 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -60,12 +60,6 @@ jobs: secrets: GCP_CREDENTIALS: ${{ secrets.GCP_CREDENTIALS }} - npm_publish: - uses: viamrobotics/rdk/.github/workflows/npm-publish.yml@main - needs: test - secrets: - NPM_TOKEN: ${{ secrets.NPM_TOKEN }} - license_finder: uses: viamrobotics/rdk/.github/workflows/license_finder.yml@main diff --git a/.github/workflows/npm-bump-version.yml b/.github/workflows/npm-bump-version.yml deleted file mode 100644 index 2b1843e2a2b..00000000000 --- a/.github/workflows/npm-bump-version.yml +++ /dev/null @@ -1,49 +0,0 @@ -name: Bump remote-control Version - -concurrency: - group: ${{ github.workflow }}-${{ github.ref }} - -on: - workflow_dispatch: - inputs: - sdk_version: - required: false - type: string - description: | - Typescript SDK Version. - If specified, may be `latest`, `next`, or a specific version. - Defaults to unspecified, which will not update the TypeScript SDK. - - bump: - required: false - type: string - default: "patch" - description: | - RC version to bump to. - May be `patch`, `minor`, `major`, or a specific version. - Defaults to `patch` -jobs: - bump: - name: Bump remote-control Version - runs-on: [ubuntu-latest] - steps: - - name: Check out code - uses: actions/checkout@v3 - - - name: Bump SDK + RC Version - run: | - cd web/frontend - npm install --save --save-exact @viamrobotics/sdk@${{ inputs.sdk_version }} - npm version ${{ inputs.bump }} - - - name: Add + Commit + Open PR - uses: peter-evans/create-pull-request@v3 - with: - commit-message: "[WORKFLOW] Updating remote-control" - branch: "workflow/bump-remote-control/${{ github.ref_name }}" - delete-branch: true - base: ${{ github.ref_name }} - title: Automated remote-control Version Update - body: This is an auto-generated PR to update remote-control package versions. Check the commits to see which repos and commits are responsible for the changes. - assignees: ${{ github.actor }} - reviewers: ${{ github.actor }} diff --git a/.github/workflows/npm-publish.yml b/.github/workflows/npm-publish.yml deleted file mode 100644 index 3d8c6256f69..00000000000 --- a/.github/workflows/npm-publish.yml +++ /dev/null @@ -1,33 +0,0 @@ -name: NPM Publish - -on: - workflow_call: - secrets: - NPM_TOKEN: - required: true - workflow_dispatch: - -jobs: - publish: - if: github.repository_owner == 'viamrobotics' - runs-on: [ubuntu-latest] - container: - image: ghcr.io/viamrobotics/rdk-devenv:amd64-cache - - steps: - - name: Checkout - uses: actions/checkout@v3 - with: - persist-credentials: false - - - name: Install and Build 🔧 - run: | - npm ci --prefix ./web/frontend --audit=false - npm run build-npm --prefix ./web/frontend - - - name: Publish - uses: JS-DevTools/npm-publish@v2 - with: - token: ${{ secrets.NPM_TOKEN }} - package: ./web/frontend/package.json - access: public diff --git a/.github/workflows/releasecandidate.yml b/.github/workflows/releasecandidate.yml index daa56fe9400..05abaef4b2d 100644 --- a/.github/workflows/releasecandidate.yml +++ b/.github/workflows/releasecandidate.yml @@ -43,12 +43,6 @@ jobs: secrets: GCP_CREDENTIALS: ${{ secrets.GCP_CREDENTIALS }} - npm_publish: - uses: viamrobotics/rdk/.github/workflows/npm-publish.yml@main - needs: test - secrets: - NPM_TOKEN: ${{ secrets.NPM_TOKEN }} - slack-workflow-status: if: ${{ failure() }} name: Post Workflow Status To Slack diff --git a/.github/workflows/stable.yml b/.github/workflows/stable.yml index 09c585b87be..6cd457b289a 100644 --- a/.github/workflows/stable.yml +++ b/.github/workflows/stable.yml @@ -60,12 +60,6 @@ jobs: secrets: GCP_CREDENTIALS: ${{ secrets.GCP_CREDENTIALS }} - npm_publish: - uses: viamrobotics/rdk/.github/workflows/npm-publish.yml@main - needs: test - secrets: - NPM_TOKEN: ${{ secrets.NPM_TOKEN }} - slack-workflow-status: if: ${{ failure() }} name: Post Workflow Status To Slack diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 0101b25fab4..594898410f4 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -202,43 +202,9 @@ jobs: pip install -r cli/test-requirements.txt check-jsonschema --schemafile ./cli/module.schema.json meta2.json - test_web_e2e: - name: Test End-to-End and Web - runs-on: ubuntu-latest - container: ghcr.io/viamrobotics/rdk-devenv:amd64-cache - timeout-minutes: 15 - steps: - - uses: actions/checkout@v3 - with: - ref: ${{ github.event_name == 'pull_request_target' && github.event.pull_request.head.sha || github.ref }} - - - name: Chown - run: chown -R testbot:testbot . - - - name: Verify no uncommitted changes from "make build-web lint-web" - run: | - sudo -Hu testbot bash -lc 'git init && git add . && make build-web lint-web' - GEN_DIFF=$(git status -s) - - if [ -n "$GEN_DIFF" ]; then - echo '"make build-web lint-web" resulted in changes not in git' 1>&2 - git status - exit 1 - fi - - - name: Install dependencies - run: | - apt-get update && apt-get -qy install libgtk2.0-0 libgtk-3-0 libgbm-dev libnotify-dev libgconf-2-4 libnss3 libxss1 libasound2 libxtst6 xauth xvfb netcat-openbsd lsof - - - name: Run web tests - run: sudo -Hu testbot bash -lc 'make test-web' - - - name: Run e2e tests - run: sudo -Hu testbot bash -lc 'make test-e2e E2E_ARGS="-k"' - test_passing: name: All Tests Passing - needs: [test_go, test_web_e2e, test32, motion_tests] + needs: [test_go, test32, motion_tests] runs-on: [ubuntu-latest] if: always() steps: @@ -246,11 +212,9 @@ jobs: run: | echo Go Unit Tests: ${{ needs.test_go.result }} echo Go 32-bit Tests: ${{ needs.test32.result }} - echo Web/E2E Tests: ${{ needs.test_web_e2e.result }} echo Motion Tests: ${{ needs.motion_tests.result }} [ "${{ needs.test_go.result }}" == "success" ] && \ [ "${{ needs.test32.result }}" == "success" ] && \ - [ "${{ needs.test_web_e2e.result }}" == "success" ] && \ [ "${{ needs.motion_tests.result }}" == "success" ] # Now that RDK is public, can't directly comment without token having full read/write access From 8afb7147e8187add7f74196499a335f9d40c14e3 Mon Sep 17 00:00:00 2001 From: abe-winter Date: Fri, 8 Nov 2024 13:27:21 -0500 Subject: [PATCH 30/51] APP-6850 update android build for go 1.23 (#4539) --- android.make | 2 ++ 1 file changed, 2 insertions(+) diff --git a/android.make b/android.make index 5b5291e4fc9..de021c41edc 100644 --- a/android.make +++ b/android.make @@ -32,8 +32,10 @@ droid-rdk.%.aar: etc/android/prefix/aarch64 etc/android/prefix/x86_64 # we clear CGO_LDFLAGS so this doesn't try (and fail) to link to linuxbrew where present $(eval JNI_ARCH := $(if $(filter arm64,$*),arm64-v8a,x86_64)) $(eval CPU_ARCH := $(if $(filter arm64,$*),aarch64,x86_64)) + # checklinkname here is from https://github.com/wlynxg/anet#how-to-build-with-go-1230-or-later CGO_LDFLAGS= PKG_CONFIG_PATH=$(DROID_PREFIX)/$(CPU_ARCH)/lib/pkgconfig \ gomobile bind -v -target android/$* -androidapi 28 -tags no_cgo \ + -ldflags="-checklinkname=0" \ -o $@ ./web/cmd/droid rm -rf droidtmp/jni/$(JNI_ARCH) mkdir -p droidtmp/jni/$(JNI_ARCH) From 375a35fdc4810f6df162c3fa8095d311a9f62da8 Mon Sep 17 00:00:00 2001 From: Dan Gottlieb Date: Fri, 8 Nov 2024 13:48:15 -0500 Subject: [PATCH 31/51] RSDK-8611: Have test make a tls config copy to avoid concurrent access. (#4544) --- robot/impl/local_robot_test.go | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index a2e37c37132..a9ad4d75525 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -560,8 +560,13 @@ func TestConfigRemoteWithTLSAuth(t *testing.T) { } test.That(t, setupLocalRobot(t, context.Background(), remoteConfig, logger).Close(context.Background()), test.ShouldBeNil) + // Create a clone such that the prior launched robot and the next robot can have their own tls + // config object to safely read from. + remoteConfig.Network.NetworkConfigData.TLSConfig = options.Network.TLSConfig.Clone() + remoteTLSConfig = remoteConfig.Network.NetworkConfigData.TLSConfig // use cert remoteTLSConfig.Certificates = []tls.Certificate{cert} + remoteTLSConfig.ServerName = "somename" test.That(t, setupLocalRobot(t, context.Background(), remoteConfig, logger).Close(context.Background()), test.ShouldBeNil) // use cert with mDNS From 5bf744c4707595fd0d73bcff74d8c8e396433a91 Mon Sep 17 00:00:00 2001 From: Dan Gottlieb Date: Fri, 8 Nov 2024 13:48:33 -0500 Subject: [PATCH 32/51] RSDK-8837: Remove the short timeout for testing reconnects that are expected to succeed. (#4541) --- robot/impl/local_robot_test.go | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index a9ad4d75525..d580075613f 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -3576,11 +3576,14 @@ func TestMachineStatus(t *testing.T) { }) } -// dialWithShortTimeout chooses a smaller timeout value to keep the test. -func dialWithShortTimeout(client *client.RobotClient) error { +// assertDialFails reconnects an existing `RobotClient` with a small timeout value to keep tests +// fast. +func assertDialFails(t *testing.T, client *client.RobotClient) { + t.Helper() ctx, done := context.WithTimeout(context.Background(), 500*time.Millisecond) defer done() - return client.Connect(ctx) + err := client.Connect(ctx) + test.That(t, err, test.ShouldNotBeNil) } // TestStickyWebRTCConnection ensures that once a RobotClient object makes a WebRTC connection, it @@ -3606,8 +3609,7 @@ func TestStickyWebRTCConnection(t *testing.T) { robot.StopWeb() // Explicitly reconnect the RobotClient. The "web" is down therefore this client will time out // and error. - connectionErr = dialWithShortTimeout(robotClient) - test.That(t, connectionErr, test.ShouldNotBeNil) + assertDialFails(t, robotClient) // Massage the options to restart the "web" on the same port as before. Note: this can result in // a test bug/failure as another test may have picked up the same port in the meantime. @@ -3617,14 +3619,13 @@ func TestStickyWebRTCConnection(t *testing.T) { test.That(t, err, test.ShouldBeNil) // Explicitly reconnect with the robot client. Reconnecting will succeed, and this should be a - // WebRTC connection. - connectionErr = dialWithShortTimeout(robotClient) + // WebRTC connection. Because this reconnect should succeed, we do not pass in a timeout. + connectionErr = robotClient.Connect(ctx) test.That(t, connectionErr, test.ShouldBeNil) // Stop the "web" again. Assert we can no longer connect. robot.StopWeb() - connectionErr = dialWithShortTimeout(robotClient) - test.That(t, connectionErr, test.ShouldNotBeNil) + assertDialFails(t, robotClient) // Restart the "web" but only accept direct gRPC connections. options.DisallowWebRTC = true @@ -3633,8 +3634,7 @@ func TestStickyWebRTCConnection(t *testing.T) { // Explicitly reconnect with the RobotClient. The RobotClient should only try creating a WebRTC // connection and thus fail this attempt. - connectionErr = dialWithShortTimeout(robotClient) - test.That(t, connectionErr, test.ShouldNotBeNil) + assertDialFails(t, robotClient) // However, a new RobotClient should happily create a direct gRPC connection. cleanClient, err := client.New(ctx, addr, logger.Sublogger("clean_client")) From 2a1cd8b7d4579a51227fd8e133de0f89be49a017 Mon Sep 17 00:00:00 2001 From: Eliot Horowitz Date: Sat, 9 Nov 2024 17:08:22 -0500 Subject: [PATCH 33/51] make errors reported during discovery (#4546) --- resource/discovery.go | 3 ++- robot/impl/discovery_test.go | 2 +- robot/impl/local_robot.go | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/resource/discovery.go b/resource/discovery.go index 87c6e981b33..9b2a11f6cba 100644 --- a/resource/discovery.go +++ b/resource/discovery.go @@ -31,11 +31,12 @@ type ( // DiscoverError indicates that a Discover function has returned an error. DiscoverError struct { Query DiscoveryQuery + Cause error } ) func (e *DiscoverError) Error() string { - return fmt.Sprintf("failed to get discovery for api %q and model %q", e.Query.API, e.Query.Model) + return fmt.Sprintf("failed to get discovery for api %q and model %q error: %v", e.Query.API, e.Query.Model, e.Cause) } // NewDiscoveryQuery returns a discovery query for a given API and model. diff --git a/robot/impl/discovery_test.go b/robot/impl/discovery_test.go index 4b29ca040d5..31c68be3044 100644 --- a/robot/impl/discovery_test.go +++ b/robot/impl/discovery_test.go @@ -90,7 +90,7 @@ func TestDiscovery(t *testing.T) { t.Run("failing Discover", func(t *testing.T) { r := setupLocalRobotWithFakeConfig(t) _, err := r.DiscoverComponents(context.Background(), []resource.DiscoveryQuery{failQ}) - test.That(t, err, test.ShouldBeError, &resource.DiscoverError{failQ}) + test.That(t, err, test.ShouldBeError, &resource.DiscoverError{Query: failQ, Cause: errFailed}) }) t.Run("working Discover", func(t *testing.T) { diff --git a/robot/impl/local_robot.go b/robot/impl/local_robot.go index a49ac0d4661..969233670c1 100644 --- a/robot/impl/local_robot.go +++ b/robot/impl/local_robot.go @@ -1108,7 +1108,7 @@ func (r *localRobot) DiscoverComponents(ctx context.Context, qs []resource.Disco if reg.Discover != nil { discovered, err := reg.Discover(ctx, r.logger.Sublogger("discovery"), q.Extra) if err != nil { - return nil, &resource.DiscoverError{Query: q} + return nil, &resource.DiscoverError{Query: q, Cause: err} } discoveries = append(discoveries, resource.Discovery{Query: q, Results: discovered}) } From 123317071919b779a9a926dfb48a9b9f1be2479c Mon Sep 17 00:00:00 2001 From: Naomi Pentrel <5212232+npentrel@users.noreply.github.com> Date: Mon, 11 Nov 2024 11:56:18 +0100 Subject: [PATCH 34/51] Update gripper.go (#4540) --- components/gripper/gripper.go | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/components/gripper/gripper.go b/components/gripper/gripper.go index 9014e5561df..bb16872ad8d 100644 --- a/components/gripper/gripper.go +++ b/components/gripper/gripper.go @@ -41,14 +41,14 @@ func Named(name string) resource.Name { // // Open example: // -// myGripper, err := gripper.FromRobot(machine, "my-gripper") +// myGripper, err := gripper.FromRobot(machine, "my_gripper") // // // Open the gripper. // err := myGripper.Open(context.Background(), nil) // // Grab example: // -// myGripper, err := gripper.FromRobot(machine, "my-gripper") +// myGripper, err := gripper.FromRobot(machine, "my_gripper") // // // Grab with the gripper. // grabbed, err := myGripper.Grab(context.Background(), nil) From 95f3f42c8efd84dd1ab9bead902ea98b5df7dc95 Mon Sep 17 00:00:00 2001 From: Maxim Pertsov Date: Mon, 11 Nov 2024 11:38:16 -0500 Subject: [PATCH 35/51] RSDK-9090 clarify package cleanup (#4542) --- robot/packages/utils.go | 59 +++++++++++++++++++++++++++-------------- 1 file changed, 39 insertions(+), 20 deletions(-) diff --git a/robot/packages/utils.go b/robot/packages/utils.go index b7976cac462..577ffcad7c2 100644 --- a/robot/packages/utils.go +++ b/robot/packages/utils.go @@ -14,7 +14,6 @@ import ( "strings" "time" - "go.uber.org/multierr" "go.viam.com/utils" "go.viam.com/rdk/config" @@ -110,7 +109,7 @@ func installPackage( } func cleanup(packagesDir string, p config.PackageConfig) error { - return multierr.Combine( + return errors.Join( os.RemoveAll(p.LocalDataDirectory(packagesDir)), os.Remove(p.LocalDownloadPath(packagesDir)), ) @@ -236,7 +235,7 @@ func unpackFile(ctx context.Context, fromFile, toDir string) error { } // commonCleanup is a helper for the various ManagerSyncer.Cleanup functions. -func commonCleanup(logger logging.Logger, expectedPackageDirectories map[string]bool, packagesDataDir string) error { +func commonCleanup(logger logging.Logger, expectedPackageEntries map[string]bool, packagesDataDir string) error { topLevelFiles, err := os.ReadDir(packagesDataDir) if err != nil { return err @@ -248,49 +247,69 @@ func commonCleanup(logger logging.Logger, expectedPackageDirectories map[string] for _, packageTypeDir := range topLevelFiles { packageTypeDirName, err := rutils.SafeJoinDir(packagesDataDir, packageTypeDir.Name()) if err != nil { - allErrors = multierr.Append(allErrors, err) + allErrors = errors.Join(allErrors, err) continue } - // There should be no non-dir files in the packages/data dir - // except .status.json and .first_run_succeeded. Delete any that exist + // Delete any non-directory files in the packages/data dir except for those with suffixes: + // + // `.status.json` - these files contain download status infomration. + // `.first_run_succeeded` - these mark successful setup phase runs. if packageTypeDir.Type()&os.ModeDir != os.ModeDir && !strings.HasSuffix(packageTypeDirName, statusFileExt) { - allErrors = multierr.Append(allErrors, os.Remove(packageTypeDirName)) + allErrors = errors.Join(allErrors, os.Remove(packageTypeDirName)) continue } - // read all of the packages in the directory and delete those that aren't in expectedPackageDirectories + // read all of the packages in the directory and delete those that aren't in expectedPackageEntries packageDirs, err := os.ReadDir(packageTypeDirName) if err != nil { - allErrors = multierr.Append(allErrors, err) + allErrors = errors.Join(allErrors, err) continue } - for _, packageDir := range packageDirs { - packageDirName, err := rutils.SafeJoinDir(packageTypeDirName, packageDir.Name()) + for _, entry := range packageDirs { + entryPath, err := rutils.SafeJoinDir(packageTypeDirName, entry.Name()) if err != nil { - allErrors = multierr.Append(allErrors, err) + allErrors = errors.Join(allErrors, err) continue } - _, expectedToExist := expectedPackageDirectories[packageDirName] - _, expectedStatusFileToExist := expectedPackageDirectories[strings.TrimSuffix(packageDirName, statusFileExt)] - _, expectedFirstRunSuccessFileToExist := expectedPackageDirectories[strings.TrimSuffix(packageDirName, config.FirstRunSuccessSuffix)] - if !expectedToExist && !expectedStatusFileToExist && !expectedFirstRunSuccessFileToExist { - logger.Debugf("Removing old package file(s) %s", packageDirName) - allErrors = multierr.Append(allErrors, os.RemoveAll(packageDirName)) + if deletePackageEntry(expectedPackageEntries, entryPath) { + logger.Debugf("Removing old package file(s) %s", entryPath) + allErrors = errors.Join(allErrors, os.RemoveAll(entryPath)) } } // re-read the directory, if there is nothing left in it, delete the directory packageDirs, err = os.ReadDir(packageTypeDirName) if err != nil { - allErrors = multierr.Append(allErrors, err) + allErrors = errors.Join(allErrors, err) continue } if len(packageDirs) == 0 { - allErrors = multierr.Append(allErrors, os.RemoveAll(packageTypeDirName)) + allErrors = errors.Join(allErrors, os.RemoveAll(packageTypeDirName)) } } return allErrors } +// deletePackageEntry checks if a file or directory in the modules data directory should be deleted or not. +func deletePackageEntry(expectedPackageEntries map[string]bool, entryPath string) bool { + // check if directory corresponds to a module version that is still managed by the package + // manager - if so DO NOT delete it. + if _, ok := expectedPackageEntries[entryPath]; ok { + return false + } + // check if directory corresponds to a module version download status file - if so DO NOT delete it. + if _, ok := expectedPackageEntries[strings.TrimSuffix(entryPath, statusFileExt)]; ok { + return false + } + // check if directory corresponds to a first run success marker file - if so DO NOT delete it. + if _, ok := expectedPackageEntries[strings.TrimSuffix(entryPath, config.FirstRunSuccessSuffix)]; ok { + return false + } + + // if we reached this point then this directory or file does not correspond to an actively-managed + // module version, and it can safely be deleted. + return true +} + type syncStatus string const ( From b208d2cb192e02ca1abcd74f588d992baab8bd03 Mon Sep 17 00:00:00 2001 From: Dan Gottlieb Date: Mon, 11 Nov 2024 11:38:35 -0500 Subject: [PATCH 36/51] RSDK-9240: Remove github action code coverage stuff we do not use. (#4548) --- .github/workflows/code-coverage-comment.yml | 17 ----- .github/workflows/test.yml | 71 --------------------- 2 files changed, 88 deletions(-) diff --git a/.github/workflows/code-coverage-comment.yml b/.github/workflows/code-coverage-comment.yml index be0f95b73b2..d8304fda3fd 100644 --- a/.github/workflows/code-coverage-comment.yml +++ b/.github/workflows/code-coverage-comment.yml @@ -11,23 +11,6 @@ jobs: runs-on: ubuntu-latest if: ${{ github.event.workflow_run.event == 'pull_request_target' && github.event.workflow_run.conclusion == 'success' }} steps: - - name: Download Code Coverage - uses: actions/download-artifact@v4 - with: - run-id: ${{ github.event.workflow_run.id }} - name: pr-code-coverage - - - name: Restore Environment - run: cat pr.env >> "${GITHUB_ENV}" - - - name: Add Coverage PR Comment - uses: marocchino/sticky-pull-request-comment@v2 - with: - header: code-coverage - number: ${{ env.PR_NUMBER }} - recreate: true - path: code-coverage-results.md - - name: Add AppImage Links if: ${{ env.APPIMAGE }} uses: marocchino/sticky-pull-request-comment@v2 diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 594898410f4..ab1a91ed69b 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -84,77 +84,6 @@ jobs: path: json.log retention-days: 30 - test_coverage: - name: Go Coverage Tests - if: false # toggle this off, delete after 3/1/24 if nobody misses it - # note: we split 'test_go' and 'test_coverage' steps because running race-detection + covprofile simultaneously is slow enough to cause flakes - strategy: - fail-fast: false - matrix: - include: - - arch: ubuntu-large - image: ghcr.io/viamrobotics/rdk-devenv:amd64-cache - platform: linux/amd64 - platform_name: linux-amd64 - - arch: ubuntu-large-arm - image: ghcr.io/viamrobotics/rdk-devenv:arm64-cache - platform: linux/arm64 - platform_name: linux-arm64 - runs-on: ${{ matrix.arch }} - container: - image: ${{ matrix.image }} - options: --platform ${{ matrix.platform }} - timeout-minutes: 30 - - steps: - - uses: actions/checkout@v3 - with: - ref: ${{ github.event_name == 'pull_request_target' && github.event.pull_request.head.sha || github.event.ref }} - fetch-depth: ${{ github.event_name == 'pull_request_target' && '0' || '1' }} # 0 aka full history, so we can analyze history for coverage - - - name: Set main env vars - if: github.event_name != 'pull_request_target' - run: | - echo "GITHUB_X_HEAD_SHA=${GITHUB_SHA}" >> $GITHUB_ENV - echo "GITHUB_X_HEAD_REF=${GITHUB_REF_NAME}" >> $GITHUB_ENV - - - name: Set PR env vars - if: github.event_name == 'pull_request_target' - env: - GITHUB_HEAD_REF_SAN: ${{ github.event.pull_request.head.label }} - run: | - echo "GITHUB_X_HEAD_SHA=${{ github.event.pull_request.head.sha }}" >> $GITHUB_ENV - echo "GITHUB_X_HEAD_REF=${GITHUB_HEAD_REF_SAN}" >> $GITHUB_ENV - echo "GITHUB_X_PR_BASE_SHA=${{ github.event.pull_request.base.sha }}" >> $GITHUB_ENV - echo "GITHUB_X_PR_BASE_REF=${{ github.event.pull_request.base.ref }}" >> $GITHUB_ENV - - - name: chown - run: chown -R testbot:testbot . - - - name: Verify no uncommitted changes from "make build-go lint-go generate-go" - run: | - sudo -Hu testbot bash -lc 'git init && git add . && make build-go lint-go generate-go' - GEN_DIFF=$(git status -s) - - if [ -n "$GEN_DIFF" ]; then - echo '"make build-go lint-go generate-go" resulted in changes not in git' 1>&2 - git status - exit 1 - fi - - - name: Run go coverage tests - run: | - sudo --preserve-env=MONGODB_TEST_OUTPUT_URI,GITHUB_SHA,GITHUB_RUN_ID,GITHUB_RUN_NUMBER,GITHUB_RUN_ATTEMPT,GITHUB_X_PR_BASE_SHA,GITHUB_X_PR_BASE_REF,GITHUB_X_HEAD_REF,GITHUB_X_HEAD_SHA,GITHUB_REPOSITORY -Hu testbot bash -lc 'make cover-only' - - - name: Upload code coverage - uses: actions/upload-artifact@v4 - with: - name: pr-code-coverage - path: | - pr.env - code-coverage-results.md - retention-days: 1 - test32: name: Go 32-bit Unit Tests runs-on: ubuntu-large-arm From 0b8597531152bb29e7c149d4363eeb9aaebf4331 Mon Sep 17 00:00:00 2001 From: nicksanford Date: Mon, 11 Nov 2024 12:50:45 -0500 Subject: [PATCH 37/51] [Data-3312] add basic data capture support for capturing tabular data to mongo (#4486) Co-authored-by: Devin Hilly --- data/bson_utils.go | 50 +++++ data/bson_utils_test.go | 186 ++++++++++++++++++ data/capture_buffer.go | 4 +- data/collector.go | 71 ++++++- data/registry.go | 20 +- etc/analyzecoverage/main.go | 5 +- etc/analyzetests/main.go | 5 +- go.mod | 2 +- go.sum | 9 +- services/datamanager/builtin/builtin.go | 4 +- services/datamanager/builtin/builtin_test.go | 2 +- .../datamanager/builtin/capture/capture.go | 126 ++++++++++-- .../datamanager/builtin/capture/config.go | 14 ++ services/datamanager/builtin/config.go | 8 +- vision/training.go | 7 +- 15 files changed, 461 insertions(+), 52 deletions(-) create mode 100644 data/bson_utils.go create mode 100644 data/bson_utils_test.go diff --git a/data/bson_utils.go b/data/bson_utils.go new file mode 100644 index 00000000000..4428e1df2af --- /dev/null +++ b/data/bson_utils.go @@ -0,0 +1,50 @@ +package data + +import ( + "fmt" + + "go.mongodb.org/mongo-driver/bson" + "google.golang.org/protobuf/types/known/structpb" +) + +// pbStructToBSON converts a structpb.Struct to a bson.M. +func pbStructToBSON(s *structpb.Struct) (bson.M, error) { + bsonMap := make(bson.M) + for k, v := range s.Fields { + bsonValue, err := convertPBStructValueToBSON(v) + if err != nil { + return nil, err + } + bsonMap[k] = bsonValue + } + return bsonMap, nil +} + +func convertPBStructValueToBSON(v *structpb.Value) (interface{}, error) { + switch v.Kind.(type) { + case *structpb.Value_NullValue: + var ret interface{} + return ret, nil + case *structpb.Value_NumberValue: + return v.GetNumberValue(), nil + case *structpb.Value_StringValue: + return v.GetStringValue(), nil + case *structpb.Value_BoolValue: + return v.GetBoolValue(), nil + case *structpb.Value_StructValue: + return pbStructToBSON(v.GetStructValue()) + case *structpb.Value_ListValue: + list := v.GetListValue() + var slice bson.A + for _, item := range list.Values { + bsonValue, err := convertPBStructValueToBSON(item) + if err != nil { + return nil, err + } + slice = append(slice, bsonValue) + } + return slice, nil + default: + return nil, fmt.Errorf("unsupported value type: %T", v.Kind) + } +} diff --git a/data/bson_utils_test.go b/data/bson_utils_test.go new file mode 100644 index 00000000000..a43b5fc9b30 --- /dev/null +++ b/data/bson_utils_test.go @@ -0,0 +1,186 @@ +package data + +import ( + "encoding/json" + "fmt" + "testing" + + "github.com/google/uuid" + "go.mongodb.org/mongo-driver/bson" + "go.mongodb.org/mongo-driver/bson/primitive" + "go.viam.com/test" + "google.golang.org/protobuf/types/known/structpb" +) + +// bsonToStructPB converts a bson.M to a structpb.Struct. +func bsonToStructPB(bsonMap bson.M) (*structpb.Struct, error) { + s := &structpb.Struct{ + Fields: make(map[string]*structpb.Value), + } + for k, v := range bsonMap { + value, err := convertBSONValueToStructPBValue(v) + if err != nil { + return nil, err + } + s.Fields[k] = value + } + return s, nil +} + +func convertBSONValueToStructPBValue(v interface{}) (*structpb.Value, error) { + switch val := v.(type) { + case nil, primitive.Undefined: + return &structpb.Value{Kind: &structpb.Value_NullValue{}}, nil + case float64: + return &structpb.Value{Kind: &structpb.Value_NumberValue{NumberValue: val}}, nil + case int64: + return &structpb.Value{Kind: &structpb.Value_NumberValue{NumberValue: float64(val)}}, nil + case int32: + return &structpb.Value{Kind: &structpb.Value_NumberValue{NumberValue: float64(val)}}, nil + case string: + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: val}}, nil + case bool: + return &structpb.Value{Kind: &structpb.Value_BoolValue{BoolValue: val}}, nil + case bson.M: + s, err := bsonToStructPB(val) + if err != nil { + return nil, err + } + return &structpb.Value{Kind: &structpb.Value_StructValue{StructValue: s}}, nil + case bson.A: + list := &structpb.ListValue{} + for _, item := range val { + value, err := convertBSONValueToStructPBValue(item) + if err != nil { + return nil, err + } + list.Values = append(list.Values, value) + } + return &structpb.Value{Kind: &structpb.Value_ListValue{ListValue: list}}, nil + case primitive.DateTime: + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: val.Time().String()}}, nil + case primitive.Timestamp: + jsonStr, err := json.Marshal(val) + if err != nil { + return nil, err + } + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: string(jsonStr)}}, nil + case primitive.JavaScript: + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: string(val)}}, nil + case primitive.Symbol: + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: string(val)}}, nil + case primitive.DBPointer, primitive.CodeWithScope, primitive.Decimal128, primitive.Regex, primitive.ObjectID: + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: val.(fmt.Stringer).String()}}, nil + case primitive.MinKey: + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: "MinKey"}}, nil + case primitive.MaxKey: + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: "MaxKey"}}, nil + case primitive.Binary: + // If it's a UUID, return the UUID as a hex string. + if val.Subtype == bson.TypeBinaryUUID { + data, err := uuid.FromBytes(val.Data) + if err != nil { + return nil, err + } + return &structpb.Value{Kind: &structpb.Value_StringValue{StringValue: data.String()}}, nil + } + + // Otherwise return a list of the raw bytes. + list := make([]*structpb.Value, len(val.Data)) + for i, b := range val.Data { + list[i] = &structpb.Value{Kind: &structpb.Value_NumberValue{NumberValue: float64(b)}} + } + return &structpb.Value{Kind: &structpb.Value_ListValue{ListValue: &structpb.ListValue{Values: list}}}, nil + default: + return nil, fmt.Errorf("unsupported BSON type: %T", v) + } +} + +func TestBSONToStructPBAndBack(t *testing.T) { + tests := []struct { + name string + input *structpb.Struct + expectedBSON primitive.M + }{ + { + name: "Primitive fields are properly converted between structpb.Struct <-> BSON.", + input: &structpb.Struct{ + Fields: map[string]*structpb.Value{ + "name": {Kind: &structpb.Value_StringValue{StringValue: "John"}}, + "age": {Kind: &structpb.Value_NumberValue{NumberValue: 30}}, + "alive": {Kind: &structpb.Value_BoolValue{BoolValue: true}}, + "nullable": {Kind: &structpb.Value_NullValue{}}, + }, + }, + expectedBSON: bson.M{ + "name": "John", + "age": 30.0, + "alive": true, + "nullable": nil, + }, + }, + { + name: "Nested struct fields are properly converted between structpb.Struct <-> BSON.", + input: &structpb.Struct{ + Fields: map[string]*structpb.Value{ + "person": { + Kind: &structpb.Value_StructValue{ + StructValue: &structpb.Struct{ + Fields: map[string]*structpb.Value{ + "name": {Kind: &structpb.Value_StringValue{StringValue: "Alice"}}, + "age": {Kind: &structpb.Value_NumberValue{NumberValue: 25}}, + "alive": {Kind: &structpb.Value_BoolValue{BoolValue: true}}, + }, + }, + }, + }, + }, + }, + expectedBSON: bson.M{ + "person": bson.M{ + "name": "Alice", + "age": float64(25), + "alive": true, + }, + }, + }, + { + name: "List fields are properly converted between structpb.Struct <-> BSON.", + input: &structpb.Struct{ + Fields: map[string]*structpb.Value{ + "names": { + Kind: &structpb.Value_ListValue{ + ListValue: &structpb.ListValue{ + Values: []*structpb.Value{ + {Kind: &structpb.Value_StringValue{StringValue: "Bob"}}, + {Kind: &structpb.Value_StringValue{StringValue: "Charlie"}}, + }, + }, + }, + }, + }, + }, + expectedBSON: bson.M{ + "names": bson.A{"Bob", "Charlie"}, + }, + }, + } + + for _, tc := range tests { + t.Run(tc.name, func(t *testing.T) { + // Convert StructPB to BSON + bsonMap, err := pbStructToBSON(tc.input) + test.That(t, err, test.ShouldBeNil) + + // Validate the BSON is structured as expected. + test.That(t, bsonMap, test.ShouldResemble, tc.expectedBSON) + + // Convert BSON back to StructPB + result, err := bsonToStructPB(bsonMap) + test.That(t, err, test.ShouldBeNil) + + // Check if the result matches the original input + test.That(t, result, test.ShouldResemble, tc.input) + }) + } +} diff --git a/data/capture_buffer.go b/data/capture_buffer.go index 0989efcae57..93edc43025e 100644 --- a/data/capture_buffer.go +++ b/data/capture_buffer.go @@ -6,6 +6,8 @@ import ( v1 "go.viam.com/api/app/datasync/v1" ) +const captureAllFromCamera = "CaptureAllFromCamera" + // CaptureBufferedWriter is a buffered, persistent queue of SensorData. type CaptureBufferedWriter interface { Write(item *v1.SensorData) error @@ -63,7 +65,7 @@ func (b *CaptureBuffer) Write(item *v1.SensorData) error { // We want to special case on "CaptureAllFromCamera" because it is sensor data that contains images // and their corresponding annotations. We want each image and its annotations to be stored in a // separate file. - } else if b.nextFile.Size() > b.maxCaptureFileSize || b.MetaData.MethodName == "CaptureAllFromCamera" { + } else if b.nextFile.Size() > b.maxCaptureFileSize || b.MetaData.MethodName == captureAllFromCamera { if err := b.nextFile.Close(); err != nil { return err } diff --git a/data/collector.go b/data/collector.go index 948d74768b1..7070141147e 100644 --- a/data/collector.go +++ b/data/collector.go @@ -11,6 +11,8 @@ import ( "github.com/benbjohnson/clock" "github.com/pkg/errors" + "go.mongodb.org/mongo-driver/bson" + "go.mongodb.org/mongo-driver/mongo" "go.opencensus.io/trace" v1 "go.viam.com/api/app/datasync/v1" pb "go.viam.com/api/common/v1" @@ -58,9 +60,14 @@ type Collector interface { type collector struct { clock clock.Clock captureResults chan *v1.SensorData - captureErrors chan error - interval time.Duration - params map[string]*anypb.Any + + mongoCollection *mongo.Collection + componentName string + componentType string + methodName string + captureErrors chan error + interval time.Duration + params map[string]*anypb.Any // `lock` serializes calls to `Flush` and `Close`. lock sync.Mutex logger logging.Logger @@ -257,7 +264,11 @@ func NewCollector(captureFunc CaptureFunc, params CollectorParams) (Collector, e c = params.Clock } return &collector{ + componentName: params.ComponentName, + componentType: params.ComponentType, + methodName: params.MethodName, captureResults: make(chan *v1.SensorData, params.QueueSize), + mongoCollection: params.MongoCollection, captureErrors: make(chan error, params.QueueSize), interval: params.Interval, params: params.MethodParams, @@ -285,10 +296,64 @@ func (c *collector) writeCaptureResults() { c.logger.Error(errors.Wrap(err, fmt.Sprintf("failed to write to collector %s", c.target.Path())).Error()) return } + + c.maybeWriteToMongo(msg) } } } +// TabularData is a denormalized sensor reading. +type TabularData struct { + TimeRequested time.Time `bson:"time_requested"` + TimeReceived time.Time `bson:"time_received"` + ComponentName string `bson:"component_name"` + ComponentType string `bson:"component_type"` + MethodName string `bson:"method_name"` + Data bson.M `bson:"data"` +} + +// maybeWriteToMongo will write to the mongoCollection +// if it is non-nil and the msg is tabular data +// logs errors on failure. +func (c *collector) maybeWriteToMongo(msg *v1.SensorData) { + if c.mongoCollection == nil { + return + } + + // DATA-3338: + // currently vision.CaptureAllFromCamera and camera.GetImages are stored in .capture files as VERY LARGE + // tabular sensor data + // That is a mistake which we are rectifying but in the meantime we don't want data captured from those methods to be synced + // to mongo + if getDataType(c.methodName) == v1.DataType_DATA_TYPE_BINARY_SENSOR || c.methodName == captureAllFromCamera { + return + } + + s := msg.GetStruct() + if s == nil { + return + } + + data, err := pbStructToBSON(s) + if err != nil { + c.logger.Error(errors.Wrap(err, "failed to convert sensor data into bson")) + return + } + + td := TabularData{ + TimeRequested: msg.Metadata.TimeRequested.AsTime(), + TimeReceived: msg.Metadata.TimeReceived.AsTime(), + ComponentName: c.componentName, + ComponentType: c.componentType, + MethodName: c.methodName, + Data: data, + } + + if _, err := c.mongoCollection.InsertOne(c.cancelCtx, td); err != nil { + c.logger.Error(errors.Wrap(err, "failed to write to mongo")) + } +} + func (c *collector) logCaptureErrs() { for err := range c.captureErrors { now := c.clock.Now().Unix() diff --git a/data/registry.go b/data/registry.go index d534e1b09c3..d48997893ed 100644 --- a/data/registry.go +++ b/data/registry.go @@ -7,6 +7,7 @@ import ( "github.com/benbjohnson/clock" "github.com/pkg/errors" + "go.mongodb.org/mongo-driver/mongo" "google.golang.org/protobuf/types/known/anypb" "go.viam.com/rdk/logging" @@ -18,14 +19,17 @@ type CollectorConstructor func(resource interface{}, params CollectorParams) (Co // CollectorParams contain the parameters needed to construct a Collector. type CollectorParams struct { - ComponentName string - Interval time.Duration - MethodParams map[string]*anypb.Any - Target CaptureBufferedWriter - QueueSize int - BufferSize int - Logger logging.Logger - Clock clock.Clock + MongoCollection *mongo.Collection + ComponentName string + ComponentType string + MethodName string + Interval time.Duration + MethodParams map[string]*anypb.Any + Target CaptureBufferedWriter + QueueSize int + BufferSize int + Logger logging.Logger + Clock clock.Clock } // Validate validates that p contains all required parameters. diff --git a/etc/analyzecoverage/main.go b/etc/analyzecoverage/main.go index 8d10e919234..53806c19209 100644 --- a/etc/analyzecoverage/main.go +++ b/etc/analyzecoverage/main.go @@ -88,13 +88,10 @@ func mainWithArgs(ctx context.Context, _ []string, logger logging.Logger) error ctx, cancel := context.WithTimeout(ctx, 5*time.Second) defer cancel() - client, err := mongo.NewClient(options.Client().ApplyURI(mongoURI)) + client, err := mongo.Connect(ctx, options.Client().ApplyURI(mongoURI)) if err != nil { return err } - if err := client.Connect(ctx); err != nil { - return err - } if err := client.Ping(ctx, readpref.Primary()); err != nil { return multierr.Combine(err, client.Disconnect(ctx)) } diff --git a/etc/analyzetests/main.go b/etc/analyzetests/main.go index 178665e5a99..3c8fb991efb 100644 --- a/etc/analyzetests/main.go +++ b/etc/analyzetests/main.go @@ -39,13 +39,10 @@ func mainWithArgs(ctx context.Context, args []string, logger logging.Logger) err ctx, cancel := context.WithTimeout(context.Background(), 20*time.Second) defer cancel() - client, err := mongo.NewClient(options.Client().ApplyURI(mongoURI)) + client, err := mongo.Connect(ctx, options.Client().ApplyURI(mongoURI)) if err != nil { return err } - if err := client.Connect(ctx); err != nil { - return err - } if err := client.Ping(ctx, readpref.Primary()); err != nil { return multierr.Combine(err, client.Disconnect(ctx)) } diff --git a/go.mod b/go.mod index 0258bd23bf7..b97ebffb1b2 100644 --- a/go.mod +++ b/go.mod @@ -77,7 +77,7 @@ require ( github.com/viamrobotics/webrtc/v3 v3.99.10 github.com/xfmoulet/qoi v0.2.0 go-hep.org/x/hep v0.32.1 - go.mongodb.org/mongo-driver v1.11.6 + go.mongodb.org/mongo-driver v1.12.2 go.opencensus.io v0.24.0 go.uber.org/atomic v1.11.0 go.uber.org/multierr v1.11.0 diff --git a/go.sum b/go.sum index 21bb07927fa..2b1bd15d364 100644 --- a/go.sum +++ b/go.sum @@ -1373,9 +1373,6 @@ github.com/tetafro/godot v1.4.17 h1:pGzu+Ye7ZUEFx7LHU0dAKmCOXWsPjl7qA6iMGndsjPs= github.com/tetafro/godot v1.4.17/go.mod h1:2oVxTBSftRTh4+MVfUaUXR6bn2GDXCaMcOG4Dk3rfio= github.com/tetratelabs/wazero v1.2.0 h1:I/8LMf4YkCZ3r2XaL9whhA0VMyAvF6QE+O7rco0DCeQ= github.com/tetratelabs/wazero v1.2.0/go.mod h1:wYx2gNRg8/WihJfSDxA1TIL8H+GkfLYm+bIfbblu9VQ= -github.com/tidwall/pretty v1.0.0/go.mod h1:XNkn88O1ChpSDQmQeStsy+sBenx6DDtFZJxhVysOjyk= -github.com/tidwall/pretty v1.2.0 h1:RWIZEg2iJ8/g6fDDYzMpobmaoGh5OLl4AXtGUGPcqCs= -github.com/tidwall/pretty v1.2.0/go.mod h1:ITEVvHYasfjBbM0u2Pg8T2nJnzm8xPwvNhhsoaGGjNU= github.com/timakin/bodyclose v0.0.0-20200424151742-cb6215831a94/go.mod h1:Qimiffbc6q9tBWlVV6x0P9sat/ao1xEkREYPPj9hphk= github.com/timakin/bodyclose v0.0.0-20230421092635-574207250966 h1:quvGphlmUVU+nhpFa4gg4yJyTRJ13reZMDHrKwYw53M= github.com/timakin/bodyclose v0.0.0-20230421092635-574207250966/go.mod h1:27bSVNWSBOHm+qRp1T9qzaIpsWEP6TbUnei/43HK+PQ= @@ -1429,10 +1426,8 @@ github.com/wlynxg/anet v0.0.3 h1:PvR53psxFXstc12jelG6f1Lv4MWqE0tI76/hHGjh9rg= github.com/wlynxg/anet v0.0.3/go.mod h1:eay5PRQr7fIVAMbTbchTnO9gG65Hg/uYGdc7mguHxoA= github.com/xdg-go/pbkdf2 v1.0.0 h1:Su7DPu48wXMwC3bs7MCNG+z4FhcyEuz5dlvchbq0B0c= github.com/xdg-go/pbkdf2 v1.0.0/go.mod h1:jrpuAogTd400dnrH08LKmI/xc1MbPOebTwRqcT5RDeI= -github.com/xdg-go/scram v1.1.1/go.mod h1:RaEWvsqvNKKvBPvcKeFjrG2cJqOkHTiyTpzz23ni57g= github.com/xdg-go/scram v1.1.2 h1:FHX5I5B4i4hKRVRBCFRxq1iQRej7WO3hhBuJf+UUySY= github.com/xdg-go/scram v1.1.2/go.mod h1:RT/sEzTbU5y00aCK8UOx6R7YryM0iF1N2MOmC3kKLN4= -github.com/xdg-go/stringprep v1.0.3/go.mod h1:W3f5j4i+9rC0kuIEJL0ky1VpHXQU3ocBgklLGvcBnW8= github.com/xdg-go/stringprep v1.0.4 h1:XLI/Ng3O1Atzq0oBs3TWm+5ZVgkq2aqdlvP9JtoZ6c8= github.com/xdg-go/stringprep v1.0.4/go.mod h1:mPGuuIYwz7CmR2bT9j4GbQqutWS1zV24gijq1dTyGkM= github.com/xen0n/gosmopolitan v1.2.2 h1:/p2KTnMzwRexIW8GlKawsTWOxn7UHA+jCMF/V8HHtvU= @@ -1477,8 +1472,8 @@ go-simpler.org/sloglint v0.7.2/go.mod h1:US+9C80ppl7VsThQclkM7BkCHQAzuz8kHLsW3pp go.etcd.io/bbolt v1.3.2/go.mod h1:IbVyRI1SCnLcuJnV2u8VeU0CEYM7e686BmAb1XKL+uU= go.etcd.io/bbolt v1.3.3/go.mod h1:IbVyRI1SCnLcuJnV2u8VeU0CEYM7e686BmAb1XKL+uU= go.etcd.io/etcd v0.0.0-20191023171146-3cf2f69b5738/go.mod h1:dnLIgRNXwCJa5e+c6mIZCrds/GIG4ncV9HhK5PX7jPg= -go.mongodb.org/mongo-driver v1.11.6 h1:XM7G6PjiGAO5betLF13BIa5TlLUUE3uJ/2Ox3Lz1K+o= -go.mongodb.org/mongo-driver v1.11.6/go.mod h1:G9TgswdsWjX4tmDA5zfs2+6AEPpYJwqblyjsfuh8oXY= +go.mongodb.org/mongo-driver v1.12.2 h1:gbWY1bJkkmUB9jjZzcdhOL8O85N9H+Vvsf2yFN0RDws= +go.mongodb.org/mongo-driver v1.12.2/go.mod h1:/rGBTebI3XYboVmgz+Wv3Bcbl3aD0QF9zl6kDDw18rQ= go.opencensus.io v0.20.1/go.mod h1:6WKK9ahsWS3RSO+PY9ZHZUfv2irvY6gN279GOPZjmmk= go.opencensus.io v0.20.2/go.mod h1:6WKK9ahsWS3RSO+PY9ZHZUfv2irvY6gN279GOPZjmmk= go.opencensus.io v0.21.0/go.mod h1:mSImk1erAIZhrmZN+AvHh14ztQfjbGwt4TtuofqLduU= diff --git a/services/datamanager/builtin/builtin.go b/services/datamanager/builtin/builtin.go index f04ef2ec2dc..eff4c215aee 100644 --- a/services/datamanager/builtin/builtin.go +++ b/services/datamanager/builtin/builtin.go @@ -129,13 +129,13 @@ func New( } // Close releases all resources managed by data_manager. -func (b *builtIn) Close(_ context.Context) error { +func (b *builtIn) Close(ctx context.Context) error { b.logger.Info("Close START") defer b.logger.Info("Close END") b.mu.Lock() defer b.mu.Unlock() b.diskSummaryLogger.close() - b.capture.Close() + b.capture.Close(ctx) b.sync.Close() return nil } diff --git a/services/datamanager/builtin/builtin_test.go b/services/datamanager/builtin/builtin_test.go index 503c8861b88..09e31dd83fd 100644 --- a/services/datamanager/builtin/builtin_test.go +++ b/services/datamanager/builtin/builtin_test.go @@ -324,7 +324,7 @@ func TestFileDeletion(t *testing.T) { // flush and close collectors to ensure we have exactly 4 files // close capture to stop it from writing more files - b.capture.Close() + b.capture.Close(ctx) // number of capture files is based on the number of unique // collectors in the robot config used in this test diff --git a/services/datamanager/builtin/capture/capture.go b/services/datamanager/builtin/capture/capture.go index ebb5038a54e..75112cba583 100644 --- a/services/datamanager/builtin/capture/capture.go +++ b/services/datamanager/builtin/capture/capture.go @@ -10,6 +10,8 @@ import ( "github.com/benbjohnson/clock" "github.com/pkg/errors" + "go.mongodb.org/mongo-driver/mongo" + "go.mongodb.org/mongo-driver/mongo/options" goutils "go.viam.com/utils" "go.viam.com/rdk/data" @@ -26,8 +28,12 @@ import ( // writes this would be performing. const defaultCaptureQueueSize = 250 -// Default bufio.Writer buffer size in bytes. -const defaultCaptureBufferSize = 4096 +const ( + // Default bufio.Writer buffer size in bytes. + defaultCaptureBufferSize = 4096 + defaultMongoDatabaseName = "sensorData" + defaultMongoCollectionName = "readings" +) func generateMetadataKey(component, method string) string { return fmt.Sprintf("%s/%s", component, method) @@ -52,11 +58,20 @@ type Capture struct { collectorsMu sync.Mutex collectors collectors - // captureDir is only stored on Capture so that we can detect when it changs captureDir string // maxCaptureFileSize is only stored on Capture so that we can detect when it changs maxCaptureFileSize int64 + mongoMU sync.Mutex + mongo captureMongo +} + +type captureMongo struct { + // the struct members are protected by + // mu and are either all nil or all non nil + client *mongo.Client + collection *mongo.Collection + config *MongoConfig } type ( @@ -93,7 +108,11 @@ func format(c datamanager.DataCaptureConfig) string { c.Name, c.Method, c.CaptureFrequencyHz, c.CaptureQueueSize, c.AdditionalParams, c.Disabled, c.Tags, c.CaptureDirectory) } -func (c *Capture) newCollectors(collectorConfigsByResource CollectorConfigsByResource, config Config) collectors { +func (c *Capture) newCollectors( + collectorConfigsByResource CollectorConfigsByResource, + config Config, + collection *mongo.Collection, +) collectors { // Initialize or add collectors based on changes to the component configurations. newCollectors := make(map[collectorMetadata]*collectorAndConfig) for res, cfgs := range collectorConfigsByResource { @@ -112,7 +131,7 @@ func (c *Capture) newCollectors(collectorConfigsByResource CollectorConfigsByRes continue } - newCollectorAndConfig, err := c.initializeOrUpdateCollector(res, md, cfg, config) + newCollectorAndConfig, err := c.initializeOrUpdateCollector(res, md, cfg, config, collection) if err != nil { c.logger.Warnw("failed to initialize or update collector", "error", err, "resource_name", res.Name(), "metadata", md, "data capture config", format(cfg)) @@ -124,6 +143,65 @@ func (c *Capture) newCollectors(collectorConfigsByResource CollectorConfigsByRes return newCollectors } +func (c *Capture) mongoSetup(ctx context.Context, newConfig MongoConfig) *mongo.Collection { + oldConfig := c.mongo.config + if oldConfig != nil && oldConfig.Equal(newConfig) && c.mongo.client != nil { + // if we have a client & the configs are equal, reuse the existing collection + return c.mongo.collection + } + + // We now know we want a mongo connection and that we either don't have one, or we have one + // but the config has changed. + // In either case we need to close all collectors and the client connection (if one exists), + // create a new client & return the configured collection. + c.closeNoMongoMutex(ctx) + // Use the SetServerAPIOptions() method to set the Stable API version to 1 + serverAPI := options.ServerAPI(options.ServerAPIVersion1) + // Create a new client and connect to the server + client, err := mongo.Connect(ctx, options.Client().ApplyURI(newConfig.URI).SetServerAPIOptions(serverAPI)) + if err != nil { + c.logger.Warn("failed to create mongo connection with mongo_capture_config.uri") + return nil + } + database := defaultIfZeroVal(newConfig.Database, defaultMongoDatabaseName) + collection := defaultIfZeroVal(newConfig.Collection, defaultMongoCollectionName) + c.mongo = captureMongo{ + client: client, + collection: client.Database(database).Collection(collection), + config: &newConfig, + } + c.logger.Info("mongo client created") + return c.mongo.collection +} + +// mongoReconfigure shuts down the collectors when the mongo client is no longer being +// valid based on the new config and attempts to create a new mongo client when the new c +// config perscribes one. +// returns a *mongo.Collection when the new client is valid and nil when it is not. +func (c *Capture) mongoReconfigure(ctx context.Context, newConfig *MongoConfig) *mongo.Collection { + c.mongoMU.Lock() + defer c.mongoMU.Unlock() + noClient := c.mongo.client == nil + disabled := newConfig == nil || newConfig.URI == "" + + if noClient && disabled { + // if we don't have a client and the new config + // isn't asking for a mongo connection, no-op + return nil + } + + if disabled { + // if we currently have a client, and the new config is disabled + // call close to disconnect from mongo and close the collectors. + // They will be recreated later during Reconfigure without a collection. + c.closeNoMongoMutex(ctx) + return nil + } + + // If the config is enabled, setup mongo + return c.mongoSetup(ctx, *newConfig) +} + // Reconfigure reconfigures Capture. // It is only called by the builtin data manager. func (c *Capture) Reconfigure( @@ -136,7 +214,7 @@ func (c *Capture) Reconfigure( // Service is disabled, so close all collectors and clear the map so we can instantiate new ones if we enable this service. if config.CaptureDisabled { c.logger.Info("Capture Disabled") - c.Close() + c.Close(ctx) return } @@ -148,7 +226,8 @@ func (c *Capture) Reconfigure( c.logger.Infof("maximum_capture_file_size_bytes old: %d, new: %d", c.maxCaptureFileSize, config.MaximumCaptureFileSizeBytes) } - newCollectors := c.newCollectors(collectorConfigsByResource, config) + collection := c.mongoReconfigure(ctx, config.MongoConfig) + newCollectors := c.newCollectors(collectorConfigsByResource, config, collection) // If a component/method has been removed from the config, close the collector. c.collectorsMu.Lock() for md, collAndConfig := range c.collectors { @@ -164,9 +243,28 @@ func (c *Capture) Reconfigure( } // Close closes the capture manager. -func (c *Capture) Close() { +func (c *Capture) Close(ctx context.Context) { c.FlushCollectors() c.closeCollectors() + c.mongoMU.Lock() + defer c.mongoMU.Unlock() + if c.mongo.client != nil { + c.logger.Info("closing mongo connection") + goutils.UncheckedError(c.mongo.client.Disconnect(ctx)) + c.mongo = captureMongo{} + } +} + +// closeNoMongoMutex exists for cases when we need to perform close actions in a function +// which is already holding the mongoMu. +func (c *Capture) closeNoMongoMutex(ctx context.Context) { + c.FlushCollectors() + c.closeCollectors() + if c.mongo.client != nil { + c.logger.Info("closing mongo connection") + goutils.UncheckedError(c.mongo.client.Disconnect(ctx)) + c.mongo = captureMongo{} + } } // Initialize a collector for the component/method or update it if it has previously been created. @@ -176,6 +274,7 @@ func (c *Capture) initializeOrUpdateCollector( md collectorMetadata, collectorConfig datamanager.DataCaptureConfig, config Config, + collection *mongo.Collection, ) (*collectorAndConfig, error) { // TODO(DATA-451): validate method params methodParams, err := protoutils.ConvertStringMapToAnyPBMap(collectorConfig.AdditionalParams) @@ -237,10 +336,13 @@ func (c *Capture) initializeOrUpdateCollector( queueSize := defaultIfZeroVal(collectorConfig.CaptureQueueSize, defaultCaptureQueueSize) bufferSize := defaultIfZeroVal(collectorConfig.CaptureBufferSize, defaultCaptureBufferSize) collector, err := collectorConstructor(res, data.CollectorParams{ - ComponentName: collectorConfig.Name.ShortName(), - Interval: data.GetDurationFromHz(collectorConfig.CaptureFrequencyHz), - MethodParams: methodParams, - Target: data.NewCaptureBuffer(targetDir, captureMetadata, config.MaximumCaptureFileSizeBytes), + MongoCollection: collection, + ComponentName: collectorConfig.Name.ShortName(), + ComponentType: collectorConfig.Name.API.String(), + MethodName: collectorConfig.Method, + Interval: data.GetDurationFromHz(collectorConfig.CaptureFrequencyHz), + MethodParams: methodParams, + Target: data.NewCaptureBuffer(targetDir, captureMetadata, config.MaximumCaptureFileSizeBytes), // Set queue size to defaultCaptureQueueSize if it was not set in the config. QueueSize: queueSize, BufferSize: bufferSize, diff --git a/services/datamanager/builtin/capture/config.go b/services/datamanager/builtin/capture/config.go index fe8b99edefe..50836dc2acf 100644 --- a/services/datamanager/builtin/capture/config.go +++ b/services/datamanager/builtin/capture/config.go @@ -1,5 +1,17 @@ package capture +// MongoConfig is the optional data capture mongo config. +type MongoConfig struct { + URI string `json:"uri"` + Database string `json:"database"` + Collection string `json:"collection"` +} + +// Equal returns true when both MongoConfigs are equal. +func (mc MongoConfig) Equal(o MongoConfig) bool { + return mc.URI == o.URI && mc.Database == o.Database && mc.Collection == o.Collection +} + // Config is the capture config. type Config struct { // CaptureDisabled if set to true disables all data capture collectors @@ -12,4 +24,6 @@ type Config struct { // (.prog) files should be allowed to grow to before they are convered into .capture // files MaximumCaptureFileSizeBytes int64 + + MongoConfig *MongoConfig } diff --git a/services/datamanager/builtin/config.go b/services/datamanager/builtin/config.go index 526429d9cdb..1f8b9ff6777 100644 --- a/services/datamanager/builtin/config.go +++ b/services/datamanager/builtin/config.go @@ -39,9 +39,10 @@ type Config struct { CaptureDir string `json:"capture_dir"` Tags []string `json:"tags"` // Capture - CaptureDisabled bool `json:"capture_disabled"` - DeleteEveryNthWhenDiskFull int `json:"delete_every_nth_when_disk_full"` - MaximumCaptureFileSizeBytes int64 `json:"maximum_capture_file_size_bytes"` + CaptureDisabled bool `json:"capture_disabled"` + DeleteEveryNthWhenDiskFull int `json:"delete_every_nth_when_disk_full"` + MaximumCaptureFileSizeBytes int64 `json:"maximum_capture_file_size_bytes"` + MongoCaptureConfig *capture.MongoConfig `json:"mongo_capture_config"` // Sync AdditionalSyncPaths []string `json:"additional_sync_paths"` FileLastModifiedMillis int `json:"file_last_modified_millis"` @@ -89,6 +90,7 @@ func (c *Config) captureConfig() capture.Config { CaptureDir: c.getCaptureDir(), Tags: c.Tags, MaximumCaptureFileSizeBytes: maximumCaptureFileSizeBytes, + MongoConfig: c.MongoCaptureConfig, } } diff --git a/vision/training.go b/vision/training.go index 0d6d8b56777..aebf4a8cc26 100644 --- a/vision/training.go +++ b/vision/training.go @@ -31,12 +31,7 @@ type ImageTrainingStore struct { // NewImageTrainingStore TODO. func NewImageTrainingStore(ctx context.Context, mongoURI, db, collection string) (*ImageTrainingStore, error) { - client, err := mongo.NewClient(options.Client().ApplyURI(mongoURI)) - if err != nil { - return nil, err - } - - err = client.Connect(ctx) + client, err := mongo.Connect(ctx, options.Client().ApplyURI(mongoURI)) if err != nil { return nil, err } From c44454b7f65d297c37108180cb7bab69e129f7c1 Mon Sep 17 00:00:00 2001 From: martha-johnston <106617924+martha-johnston@users.noreply.github.com> Date: Tue, 12 Nov 2024 09:32:32 -0500 Subject: [PATCH 38/51] RSDK-9136: issues when stopping motor with controls (#4550) --- components/motor/gpio/basic.go | 4 ++++ components/motor/gpio/basic_test.go | 10 +++++----- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/components/motor/gpio/basic.go b/components/motor/gpio/basic.go index 298a0b9d93e..6755f4b03cb 100644 --- a/components/motor/gpio/basic.go +++ b/components/motor/gpio/basic.go @@ -102,6 +102,10 @@ func NewMotor(b board.Board, mc Config, name resource.Name, logger logging.Logge m.EnablePinLow = enablePinLow } + if m.maxRPM == 0 { + m.maxRPM = 100 + } + return m, nil } diff --git a/components/motor/gpio/basic_test.go b/components/motor/gpio/basic_test.go index ef348463fd3..ada19e63d5f 100644 --- a/components/motor/gpio/basic_test.go +++ b/components/motor/gpio/basic_test.go @@ -168,7 +168,7 @@ func TestMotorDirPWM(t *testing.T) { mc.ResourceName(), logger) test.That(t, err, test.ShouldBeNil) - test.That(t, m.GoFor(ctx, 50, 10, nil), test.ShouldBeError, errors.New("not supported, define max_rpm attribute != 0")) + test.That(t, m.GoFor(ctx, 50, 10, nil), test.ShouldBeNil) m, err = NewMotor(b, Config{Pins: PinConfig{Direction: "1", EnablePinLow: "2"}, PWMFreq: 4000}, mc.ResourceName(), logger) @@ -191,7 +191,7 @@ func TestMotorDirPWM(t *testing.T) { t.Run("motor (DIR/PWM) Off testing", func(t *testing.T) { test.That(t, m.Stop(ctx, nil), test.ShouldBeNil) - test.That(t, mustGetGPIOPinByName(b, "1").Get(context.Background()), test.ShouldEqual, false) + test.That(t, mustGetGPIOPinByName(b, "1").Get(context.Background()), test.ShouldEqual, true) test.That(t, mustGetGPIOPinByName(b, "2").Get(context.Background()), test.ShouldEqual, true) test.That(t, mustGetGPIOPinByName(b, "1").PWM(context.Background()), test.ShouldEqual, 0) test.That(t, mustGetGPIOPinByName(b, "2").PWM(context.Background()), test.ShouldEqual, 0) @@ -204,11 +204,11 @@ func TestMotorDirPWM(t *testing.T) { t.Run("motor (DIR/PWM) GoFor testing", func(t *testing.T) { test.That(t, m.GoFor(ctx, 50, 0, nil), test.ShouldBeError, motor.NewZeroRevsError()) - test.That(t, mustGetGPIOPinByName(b, "1").Get(context.Background()), test.ShouldEqual, false) + test.That(t, mustGetGPIOPinByName(b, "1").Get(context.Background()), test.ShouldEqual, true) test.That(t, mustGetGPIOPinByName(b, "3").PWM(context.Background()), test.ShouldEqual, 0) test.That(t, m.GoFor(ctx, -50, 0, nil), test.ShouldBeError, motor.NewZeroRevsError()) - test.That(t, mustGetGPIOPinByName(b, "1").Get(context.Background()), test.ShouldEqual, false) + test.That(t, mustGetGPIOPinByName(b, "1").Get(context.Background()), test.ShouldEqual, true) test.That(t, mustGetGPIOPinByName(b, "3").PWM(context.Background()), test.ShouldEqual, 0) test.That(t, m.Stop(context.Background(), nil), test.ShouldBeNil) @@ -341,7 +341,7 @@ func TestMotorABNoEncoder(t *testing.T) { test.That(t, err, test.ShouldBeNil) t.Run("motor no encoder GoFor testing", func(t *testing.T) { - test.That(t, m.GoFor(ctx, 50, 10, nil), test.ShouldBeError, errors.New("not supported, define max_rpm attribute != 0")) + test.That(t, m.GoFor(ctx, 50, 10, nil), test.ShouldBeNil) }) t.Run("motor no encoder GoTo testing", func(t *testing.T) { From d848d208bf489e52bfd9a297d4a96f172906881f Mon Sep 17 00:00:00 2001 From: martha-johnston <106617924+martha-johnston@users.noreply.github.com> Date: Wed, 13 Nov 2024 11:10:27 -0500 Subject: [PATCH 39/51] RSDK-9037: Add AttachDirectionalAwareness to DoCommand (#4552) --- components/encoder/single/single_encoder.go | 18 ++++++++++++++++++ components/motor/gpio/controlled.go | 17 ++++++++++++----- components/motor/gpio/encoded.go | 2 +- components/motor/gpio/encoded_test.go | 3 +++ components/motor/gpio/setup.go | 19 +++++++++++++------ 5 files changed, 47 insertions(+), 12 deletions(-) diff --git a/components/encoder/single/single_encoder.go b/components/encoder/single/single_encoder.go index 423ce9ff2a0..0ff3e42cf38 100644 --- a/components/encoder/single/single_encoder.go +++ b/components/encoder/single/single_encoder.go @@ -33,10 +33,16 @@ import ( "go.viam.com/rdk/components/board" "go.viam.com/rdk/components/encoder" + "go.viam.com/rdk/components/motor" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" ) +const ( + isSingle = "single" + directionAttached = "direction" +) + var singleModel = resource.DefaultModelFamily.WithModel("single") func init() { @@ -260,3 +266,15 @@ func (e *Encoder) Close(ctx context.Context) error { } return nil } + +// DoCommand uses a map string to run custom functionality of a single encoder. +func (e *Encoder) DoCommand(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error) { + resp := make(map[string]interface{}) + + if m, ok := cmd[isSingle].(motor.Motor); ok { + e.AttachDirectionalAwareness(m.(DirectionAware)) + resp[directionAttached] = true + } + + return resp, nil +} diff --git a/components/motor/gpio/controlled.go b/components/motor/gpio/controlled.go index 62ef6b3e66b..8b66664a195 100644 --- a/components/motor/gpio/controlled.go +++ b/components/motor/gpio/controlled.go @@ -101,7 +101,7 @@ func (cm *controlledMotor) startControlLoop() error { func setupMotorWithControls( _ context.Context, - m *Motor, + m motor.Motor, enc encoder.Encoder, cfg resource.Config, logger logging.Logger, @@ -116,12 +116,18 @@ func setupMotorWithControls( tpr = 1.0 } + maxRPM := float64(conf.MaxRPM) + if maxRPM == 0 { + maxRPM = 100 + } + cm := &controlledMotor{ Named: cfg.ResourceName().AsNamed(), logger: logger, opMgr: operation.NewSingleOperationManager(), tunedVals: &[]control.PIDConfig{{}}, ticksPerRotation: tpr, + maxRPM: maxRPM, real: m, enc: enc, } @@ -146,9 +152,10 @@ type controlledMotor struct { offsetInTicks float64 ticksPerRotation float64 + maxRPM float64 mu sync.RWMutex - real *Motor + real motor.Motor enc encoder.Encoder controlLoopConfig control.Config @@ -191,7 +198,7 @@ func (cm *controlledMotor) Stop(ctx context.Context, extra map[string]interface{ if err != nil { return err } - if err := cm.updateControlBlock(ctx, currentTicks+cm.offsetInTicks, cm.real.maxRPM*cm.ticksPerRotation/60); err != nil { + if err := cm.updateControlBlock(ctx, currentTicks+cm.offsetInTicks, cm.maxRPM*cm.ticksPerRotation/60); err != nil { return err } } @@ -279,7 +286,7 @@ func (cm *controlledMotor) SetRPM(ctx context.Context, rpm float64, extra map[st ctx, done := cm.opMgr.New(ctx) defer done() - warning, err := motor.CheckSpeed(rpm, cm.real.maxRPM) + warning, err := motor.CheckSpeed(rpm, cm.maxRPM) if warning != "" { cm.logger.CWarn(ctx, warning) } @@ -320,7 +327,7 @@ func (cm *controlledMotor) GoFor(ctx context.Context, rpm, revolutions float64, ctx, done := cm.opMgr.New(ctx) defer done() - warning, err := motor.CheckSpeed(rpm, cm.real.maxRPM) + warning, err := motor.CheckSpeed(rpm, cm.maxRPM) if warning != "" { cm.logger.CWarn(ctx, warning) } diff --git a/components/motor/gpio/encoded.go b/components/motor/gpio/encoded.go index 00e0d5c6dca..01e4211c424 100644 --- a/components/motor/gpio/encoded.go +++ b/components/motor/gpio/encoded.go @@ -88,8 +88,8 @@ func newEncodedMotor( } if em.rampRate == 0 || em.rampRate > 0.5 { - em.rampRate = 0.05 // Use a conservative value by default. em.logger.Warnf("setting ramp rate to default value of 0.05 instead of %v", em.rampRate) + em.rampRate = 0.05 // Use a conservative value by default. } if em.maxPowerPct < 0 || em.maxPowerPct > 1 { diff --git a/components/motor/gpio/encoded_test.go b/components/motor/gpio/encoded_test.go index 3672c213512..14132362eb0 100644 --- a/components/motor/gpio/encoded_test.go +++ b/components/motor/gpio/encoded_test.go @@ -56,6 +56,9 @@ func injectEncoder(vals *injectedState) encoder.Encoder { enc.PropertiesFunc = func(ctx context.Context, extra map[string]interface{}) (encoder.Properties, error) { return encoder.Properties{TicksCountSupported: true}, nil } + enc.DoFunc = func(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error) { + return nil, nil + } return enc } diff --git a/components/motor/gpio/setup.go b/components/motor/gpio/setup.go index 82d8e911ca6..6dc8044911c 100644 --- a/components/motor/gpio/setup.go +++ b/components/motor/gpio/setup.go @@ -7,7 +7,6 @@ import ( "go.viam.com/rdk/components/board" "go.viam.com/rdk/components/encoder" - "go.viam.com/rdk/components/encoder/single" "go.viam.com/rdk/components/motor" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" @@ -15,6 +14,11 @@ import ( var model = resource.DefaultModelFamily.WithModel("gpio") +const ( + isSingle = "single" + directionAttached = "direction" +) + // MotorType represents the three accepted pin configuration settings // supported by a gpio motor. type MotorType int @@ -185,7 +189,6 @@ func createNewMotor( } if motorConfig.Encoder != "" { - basic := m.(*Motor) e, err := encoder.FromDependencies(deps, motorConfig.Encoder) if err != nil { return nil, err @@ -200,9 +203,13 @@ func createNewMotor( encoder.NewEncodedMotorPositionTypeUnsupportedError(props) } - single, isSingle := e.(*single.Encoder) - if isSingle { - single.AttachDirectionalAwareness(basic) + cmd := make(map[string]interface{}) + cmd[isSingle] = m + resp, err := e.DoCommand(ctx, cmd) + if err != nil { + return nil, err + } + if resp != nil && resp[directionAttached].(bool) { logger.CInfo(ctx, "direction attached to single encoder from encoded motor") } @@ -213,7 +220,7 @@ func createNewMotor( return nil, err } default: - m, err = setupMotorWithControls(ctx, basic, e, cfg, logger) + m, err = setupMotorWithControls(ctx, m, e, cfg, logger) if err != nil { return nil, err } From 09e295cfe322df5b4ab017ae86eb9ad76e90b511 Mon Sep 17 00:00:00 2001 From: Kurt S <56745262+Kschappacher@users.noreply.github.com> Date: Wed, 13 Nov 2024 12:10:42 -0500 Subject: [PATCH 40/51] RSDK-8767 - populate local_name and remote_path to all resource names sent from RDK (#4519) --- protoutils/messages.go | 10 ++++++---- protoutils/messages_test.go | 17 +++++++++++++++++ resource/name.go | 8 ++++++++ resource/name_test.go | 18 ++++++++++++++++++ robot/server/server_test.go | 26 ++++++++++++++++---------- 5 files changed, 65 insertions(+), 14 deletions(-) diff --git a/protoutils/messages.go b/protoutils/messages.go index 17089355813..e7544a69ac9 100644 --- a/protoutils/messages.go +++ b/protoutils/messages.go @@ -23,10 +23,12 @@ import ( // ResourceNameToProto converts a resource.Name to its proto counterpart. func ResourceNameToProto(name resource.Name) *commonpb.ResourceName { return &commonpb.ResourceName{ - Namespace: string(name.API.Type.Namespace), - Type: name.API.Type.Name, - Subtype: name.API.SubtypeName, - Name: name.ShortName(), + Namespace: string(name.API.Type.Namespace), + Type: name.API.Type.Name, + Subtype: name.API.SubtypeName, + Name: name.ShortName(), + RemotePath: name.RemoteNameToRemoteArray(), + LocalName: name.Name, } } diff --git a/protoutils/messages_test.go b/protoutils/messages_test.go index f0e628fae40..4466cc39435 100644 --- a/protoutils/messages_test.go +++ b/protoutils/messages_test.go @@ -7,6 +7,8 @@ import ( "go.viam.com/test" "google.golang.org/protobuf/types/known/wrapperspb" + + "go.viam.com/rdk/resource" ) func TestStringToAnyPB(t *testing.T) { @@ -40,3 +42,18 @@ func TestStringToAnyPB(t *testing.T) { wrappedVal4 := wrapperspb.String("abcd") test.That(t, anyVal.MessageIs(wrappedVal4), test.ShouldBeTrue) } + +func TestResourceNameToProto(t *testing.T) { + resourceName := resource.Name{ + Name: "totallyLegitResource", + Remote: "remote1:remote2:remote3", + API: resource.NewAPI("space", "fake", "fakeFake"), + } + resourceNameProto := ResourceNameToProto(resourceName) + finalResource := ResourceNameFromProto(resourceNameProto) + + test.That(t, resourceNameProto.LocalName, test.ShouldEqual, "totallyLegitResource") + test.That(t, resourceNameProto.RemotePath, test.ShouldResemble, []string{"remote1", "remote2", "remote3"}) + test.That(t, resourceNameProto.Name, test.ShouldEqual, "remote1:remote2:remote3:totallyLegitResource") + test.That(t, finalResource, test.ShouldResemble, resourceName) +} diff --git a/resource/name.go b/resource/name.go index 42e06a4730a..1f34578e217 100644 --- a/resource/name.go +++ b/resource/name.go @@ -141,6 +141,14 @@ func (n Name) String() string { return name } +// RemoteNameToRemoteArray returns an ordered array of all of remotes in a resource name. +func (n Name) RemoteNameToRemoteArray() []string { + if n.Remote == "" { + return []string{} + } + return strings.Split(n.Remote, ":") +} + // SDPTrackName returns a valid SDP video/audio track name as defined in RFC 4566 (https://www.rfc-editor.org/rfc/rfc4566) // where track names should not include colons. func (n Name) SDPTrackName() string { diff --git a/resource/name_test.go b/resource/name_test.go index c6489b7aabe..779b8e5e8c1 100644 --- a/resource/name_test.go +++ b/resource/name_test.go @@ -191,3 +191,21 @@ func TestNamesToStrings(t *testing.T) { test.That(t, NamesToStrings(tc.input), test.ShouldResemble, tc.output) } } + +func TestRemoteNameToRemoteArray(t *testing.T) { + t.Run("name with multiple remote returns array of remotes", func(t *testing.T) { + nameTest := Name{ + Remote: "foo:bar:wow", + } + remoteArray := nameTest.RemoteNameToRemoteArray() + test.That(t, remoteArray, test.ShouldResemble, []string{"foo", "bar", "wow"}) + }) + + t.Run("name with empty remotes should return empty string array", func(t *testing.T) { + nameTest := Name{ + Remote: "", + } + remoteArray := nameTest.RemoteNameToRemoteArray() + test.That(t, remoteArray, test.ShouldResemble, []string{}) + }) +} diff --git a/robot/server/server_test.go b/robot/server/server_test.go index 3270ac69edd..130b1f03111 100644 --- a/robot/server/server_test.go +++ b/robot/server/server_test.go @@ -51,10 +51,12 @@ var serverNewResource = arm.Named("") var serverOneResourceResponse = []*commonpb.ResourceName{ { - Namespace: string(serverNewResource.API.Type.Namespace), - Type: serverNewResource.API.Type.Name, - Subtype: serverNewResource.API.SubtypeName, - Name: serverNewResource.Name, + Namespace: string(serverNewResource.API.Type.Namespace), + Type: serverNewResource.API.Type.Name, + Subtype: serverNewResource.API.SubtypeName, + Name: serverNewResource.Name, + RemotePath: []string{}, + LocalName: "", }, } @@ -325,17 +327,21 @@ func TestServer(t *testing.T) { expectedResp := []*pb.ResourceRPCSubtype{ { Subtype: &commonpb.ResourceName{ - Namespace: string(serverNewResource.API.Type.Namespace), - Type: serverNewResource.API.Type.Name, - Subtype: serverNewResource.API.SubtypeName, + Namespace: string(serverNewResource.API.Type.Namespace), + Type: serverNewResource.API.Type.Name, + Subtype: serverNewResource.API.SubtypeName, + RemotePath: []string{}, + Name: "", }, ProtoService: desc1.GetFullyQualifiedName(), }, { Subtype: &commonpb.ResourceName{ - Namespace: string(otherAPI.Type.Namespace), - Type: otherAPI.Type.Name, - Subtype: otherAPI.SubtypeName, + Namespace: string(otherAPI.Type.Namespace), + Type: otherAPI.Type.Name, + Subtype: otherAPI.SubtypeName, + RemotePath: []string{}, + Name: "", }, ProtoService: desc2.GetFullyQualifiedName(), }, From 3edf860c044e8be711b88eebf142724c8cc77c64 Mon Sep 17 00:00:00 2001 From: abe-winter Date: Wed, 13 Nov 2024 14:29:56 -0500 Subject: [PATCH 41/51] APP-6696 include `os_version` tag on GOOS=darwin (#4536) --- config/platform.go | 37 +++++++++++++++++++++++++++++-------- 1 file changed, 29 insertions(+), 8 deletions(-) diff --git a/config/platform.go b/config/platform.go index 748aa10064a..85eb9d189ad 100644 --- a/config/platform.go +++ b/config/platform.go @@ -17,14 +17,12 @@ var ( cudaRegex = regexp.MustCompile(`Cuda compilation tools, release (\d+)\.`) aptCacheVersionRegex = regexp.MustCompile(`\nVersion: (\d+)\D`) piModelRegex = regexp.MustCompile(`Raspberry Pi\s?(Compute Module)?\s?(\d\w*)?\s?(\w+)?\s?(Model (.+))? Rev`) + darwinVersionRegex = regexp.MustCompile(`(\d+)\.`) savedPlatformTags []string ) // helper to read platform tags for GPU-related system libraries. -func readGPUTags(logger logging.Logger, tags []string) []string { - // this timeout is for all steps in this function. - ctx, cancel := context.WithTimeout(context.Background(), time.Second*5) - defer cancel() +func readGPUTags(ctx context.Context, logger logging.Logger, tags []string) []string { if _, err := exec.LookPath("nvcc"); err == nil { out, err := exec.CommandContext(ctx, "nvcc", "--version").Output() if err != nil { @@ -33,7 +31,7 @@ func readGPUTags(logger logging.Logger, tags []string) []string { if match := cudaRegex.FindSubmatch(out); match != nil { tags = append(tags, "cuda:true", "cuda_version:"+string(match[1])) } else { - logger.Errorw("error parsing `nvcc --version` output. Cuda-specific modules may not load") + logger.Error("error parsing `nvcc --version` output. Cuda-specific modules may not load") } } if _, err := exec.LookPath("apt-cache"); err == nil { @@ -139,20 +137,43 @@ func readLinuxTags(logger logging.Logger, tags []string) []string { return tags } +func readDarwinTags(ctx context.Context, logger logging.Logger, tags []string) []string { + if _, err := exec.LookPath("sw_vers"); err == nil { + out, err := exec.CommandContext(ctx, "sw_vers", "--productVersion").Output() + if err != nil { + logger.Errorw("error getting darwin version from sw_vers. Mac-specific modules may not load", "err", err) + } + if match := darwinVersionRegex.FindSubmatch(out); match != nil { + tags = append(tags, "os_version:"+string(match[1])) + } else { + logger.Errorw("error parsing sw_vers version output. Mac-specific modules may not load", "input", string(out)) + } + } + return tags +} + // This reads the granular platform constraints (os version, distro, etc). // This further constrains the basic runtime.GOOS/GOARCH stuff in getAgentInfo // so module authors can publish builds with ABI or SDK dependencies. The // list of tags returned by this function is expected to grow. func readExtendedPlatformTags(logger logging.Logger, cache bool) []string { - // TODO(APP-6696): CI in multiple environments (alpine + mac), darwin support. if cache && savedPlatformTags != nil { return savedPlatformTags } + + // this timeout is for all steps in this function. + ctx, cancel := context.WithTimeout(context.Background(), time.Second*5) + defer cancel() + tags := make([]string, 0, 3) - if runtime.GOOS == "linux" { + + switch runtime.GOOS { + case "linux": tags = readLinuxTags(logger, tags) - tags = readGPUTags(logger, tags) + tags = readGPUTags(ctx, logger, tags) tags = readPiTags(logger, tags) + case "darwin": + tags = readDarwinTags(ctx, logger, tags) } if cache { savedPlatformTags = tags From b7c46354a39b2d7f95edf4ee2f104fd9bf638af2 Mon Sep 17 00:00:00 2001 From: martha-johnston <106617924+martha-johnston@users.noreply.github.com> Date: Thu, 14 Nov 2024 09:40:07 -0500 Subject: [PATCH 42/51] RSDK-8926: Rover canary motor test fail because failure to set pins (#4549) --- components/motor/gpio/basic.go | 4 ++-- robot/impl/local_robot.go | 13 +++++++------ 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/components/motor/gpio/basic.go b/components/motor/gpio/basic.go index 6755f4b03cb..bc389cea78d 100644 --- a/components/motor/gpio/basic.go +++ b/components/motor/gpio/basic.go @@ -193,7 +193,7 @@ func (m *Motor) setPWM(ctx context.Context, powerPct float64, extra map[string]i switch m.motorType { case ABPwm, DirectionPwm: if math.Abs(powerPct) <= 0.001 { - return m.turnOff(ctx, extra) + return m.turnOff(context.Background(), extra) } pwmPin = m.PWM case AB: @@ -310,7 +310,7 @@ func (m *Motor) Stop(ctx context.Context, extra map[string]interface{}) error { m.opMgr.CancelRunning(ctx) m.mu.Lock() defer m.mu.Unlock() - return m.setPWM(ctx, 0, extra) + return m.setPWM(context.Background(), 0, extra) } // IsMoving returns if the motor is currently on or off. diff --git a/robot/impl/local_robot.go b/robot/impl/local_robot.go index 969233670c1..8bcf59c3626 100644 --- a/robot/impl/local_robot.go +++ b/robot/impl/local_robot.go @@ -193,25 +193,26 @@ func (r *localRobot) StopAll(ctx context.Context, extra map[resource.Name]map[st } // Stop all stoppable resources - resourceErrs := []string{} + resourceErrs := make(map[string]error) for _, name := range r.ResourceNames() { res, err := r.ResourceByName(name) if err != nil { - resourceErrs = append(resourceErrs, name.Name) + resourceErrs[name.Name] = err continue } if actuator, ok := res.(resource.Actuator); ok { if err := actuator.Stop(ctx, extra[name]); err != nil { - resourceErrs = append(resourceErrs, name.Name) + resourceErrs[name.Name] = err } } } - if len(resourceErrs) > 0 { - return errors.Errorf("failed to stop components named %s", strings.Join(resourceErrs, ",")) + var errs error + for k, v := range resourceErrs { + errs = multierr.Combine(errs, errors.Errorf("failed to stop component named %s with error %v", k, v)) } - return nil + return errs } // Config returns a config representing the current state of the robot. From 63b76814e94947743ef9a45567c2248f37e4e760 Mon Sep 17 00:00:00 2001 From: nicksanford Date: Thu, 14 Nov 2024 12:24:38 -0500 Subject: [PATCH 43/51] [DATA-3338] - collector test improvements (#4551) --- .../arm/{collector.go => collectors.go} | 0 components/arm/collectors_test.go | 61 ++--- .../board/{collector.go => collectors.go} | 0 components/board/collectors_test.go | 61 +++-- .../camera/{collector.go => collectors.go} | 2 - components/camera/collectors_test.go | 208 ++++++++++++++++ components/camera/export_collectors_test.go | 10 + .../encoder/{collector.go => collectors.go} | 0 components/encoder/collectors_test.go | 37 ++- .../gantry/{collector.go => collectors.go} | 0 components/gantry/collectors_test.go | 47 ++-- .../motor/{collector.go => collectors.go} | 0 components/motor/collectors_test.go | 49 ++-- .../{collector.go => collectors.go} | 0 components/movementsensor/collectors_test.go | 138 ++++++----- .../{collector.go => collectors.go} | 0 components/powersensor/collectors_test.go | 71 +++--- .../sensor/{collector.go => collectors.go} | 0 .../{collector_test.go => collectors_test.go} | 35 +-- .../servo/{collector.go => collectors.go} | 0 components/servo/collectors_test.go | 37 ++- services/slam/{collector.go => collectors.go} | 0 services/slam/collectors_test.go | 125 ++++++++++ services/slam/export_collectors_test.go | 9 + .../vision/{collector.go => collectors.go} | 0 services/vision/collectors_test.go | 224 ++++++++++-------- testutils/file_utils.go | 102 ++++++-- 27 files changed, 853 insertions(+), 363 deletions(-) rename components/arm/{collector.go => collectors.go} (100%) rename components/board/{collector.go => collectors.go} (100%) rename components/camera/{collector.go => collectors.go} (99%) create mode 100644 components/camera/collectors_test.go create mode 100644 components/camera/export_collectors_test.go rename components/encoder/{collector.go => collectors.go} (100%) rename components/gantry/{collector.go => collectors.go} (100%) rename components/motor/{collector.go => collectors.go} (100%) rename components/movementsensor/{collector.go => collectors.go} (100%) rename components/powersensor/{collector.go => collectors.go} (100%) rename components/sensor/{collector.go => collectors.go} (100%) rename components/sensor/{collector_test.go => collectors_test.go} (55%) rename components/servo/{collector.go => collectors.go} (100%) rename services/slam/{collector.go => collectors.go} (100%) create mode 100644 services/slam/collectors_test.go create mode 100644 services/slam/export_collectors_test.go rename services/vision/{collector.go => collectors.go} (100%) diff --git a/components/arm/collector.go b/components/arm/collectors.go similarity index 100% rename from components/arm/collector.go rename to components/arm/collectors.go diff --git a/components/arm/collectors_test.go b/components/arm/collectors_test.go index 1313a2a7186..acd016fbc02 100644 --- a/components/arm/collectors_test.go +++ b/components/arm/collectors_test.go @@ -5,9 +5,9 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" + "github.com/benbjohnson/clock" "github.com/golang/geo/r3" - v1 "go.viam.com/api/common/v1" + datasyncpb "go.viam.com/api/app/datasync/v1" pb "go.viam.com/api/component/arm/v1" "go.viam.com/test" @@ -22,8 +22,7 @@ import ( const ( componentName = "arm" - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) var floatList = &pb.JointPositions{Values: []float64{1.0, 2.0, 3.0}} @@ -32,40 +31,50 @@ func TestCollectors(t *testing.T) { tests := []struct { name string collector data.CollectorConstructor - expected map[string]any + expected *datasyncpb.SensorData }{ { name: "End position collector should write a pose", collector: arm.NewEndPositionCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetEndPositionResponse{ - Pose: &v1.Pose{ - OX: 0, - OY: 0, - OZ: 1, - Theta: 0, - X: 1, - Y: 2, - Z: 3, - }, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "pose": map[string]any{ + "o_x": 0, + "o_y": 0, + "o_z": 1, + "theta": 0, + "x": 1, + "y": 2, + "z": 3, + }, + })}, + }, }, { name: "Joint positions collector should write a list of positions", collector: arm.NewJointPositionsCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetJointPositionsResponse{Positions: floatList}), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "positions": map[string]any{ + "values": []any{1.0, 2.0, 3.0}, + }, + })}, + }, }, } for _, tc := range tests { t.Run(tc.name, func(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: componentName, Interval: captureInterval, Logger: logging.NewTestLogger(t), - Clock: mockClock, - Target: &buf, + Clock: clock.New(), + Target: buf, } arm := newArm() @@ -74,13 +83,11 @@ func TestCollectors(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, tc.expected) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() }) } } diff --git a/components/board/collector.go b/components/board/collectors.go similarity index 100% rename from components/board/collector.go rename to components/board/collectors.go diff --git a/components/board/collectors_test.go b/components/board/collectors_test.go index 18d5c2f85d5..200ea6cd1f7 100644 --- a/components/board/collectors_test.go +++ b/components/board/collectors_test.go @@ -6,9 +6,9 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" + "github.com/benbjohnson/clock" "github.com/golang/protobuf/ptypes/wrappers" - pb "go.viam.com/api/component/board/v1" + datasyncpb "go.viam.com/api/app/datasync/v1" "go.viam.com/test" "google.golang.org/protobuf/proto" "google.golang.org/protobuf/types/known/anypb" @@ -22,18 +22,15 @@ import ( const ( componentName = "board" - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) func TestCollectors(t *testing.T) { tests := []struct { - name string - params data.CollectorParams - collector data.CollectorConstructor - expected map[string]any - shouldError bool - expectedError error + name string + params data.CollectorParams + collector data.CollectorConstructor + expected *datasyncpb.SensorData }{ { name: "Board analog collector should write an analog response", @@ -46,13 +43,15 @@ func TestCollectors(t *testing.T) { }, }, collector: board.NewAnalogCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.ReadAnalogReaderResponse{ - Value: 1, - MinRange: 0, - MaxRange: 10, - StepSize: 0.1, - }), - shouldError: false, + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "value": 1, + "min_range": 0, + "max_range": 10, + "step_size": float64(float32(0.1)), + })}, + }, }, { name: "Board gpio collector should write a gpio response", @@ -65,19 +64,21 @@ func TestCollectors(t *testing.T) { }, }, collector: board.NewGPIOCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetGPIOResponse{ - High: true, - }), - shouldError: false, + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "high": true, + })}, + }, }, } for _, tc := range tests { t.Run(tc.name, func(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} - tc.params.Clock = mockClock - tc.params.Target = &buf + start := time.Now() + buf := tu.NewMockBuffer() + tc.params.Clock = clock.New() + tc.params.Target = buf board := newBoard() col, err := tc.collector(board, tc.params) @@ -85,13 +86,11 @@ func TestCollectors(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, tc.expected) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() }) } } diff --git a/components/camera/collector.go b/components/camera/collectors.go similarity index 99% rename from components/camera/collector.go rename to components/camera/collectors.go index ba597e58a58..e2df6868189 100644 --- a/components/camera/collector.go +++ b/components/camera/collectors.go @@ -35,8 +35,6 @@ func (m method) String() string { return "Unknown" } -// TODO: add tests for this file. - func newNextPointCloudCollector(resource interface{}, params data.CollectorParams) (data.Collector, error) { camera, err := assertCamera(resource) if err != nil { diff --git a/components/camera/collectors_test.go b/components/camera/collectors_test.go new file mode 100644 index 00000000000..60af3460585 --- /dev/null +++ b/components/camera/collectors_test.go @@ -0,0 +1,208 @@ +package camera_test + +import ( + "bytes" + "context" + "encoding/base64" + "image" + "io" + "strconv" + "testing" + "time" + + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" + camerapb "go.viam.com/api/component/camera/v1" + "go.viam.com/test" + "go.viam.com/utils/artifact" + "google.golang.org/protobuf/reflect/protoreflect" + "google.golang.org/protobuf/types/known/anypb" + "google.golang.org/protobuf/types/known/timestamppb" + "google.golang.org/protobuf/types/known/wrapperspb" + + "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/data" + "go.viam.com/rdk/gostream" + "go.viam.com/rdk/logging" + "go.viam.com/rdk/pointcloud" + "go.viam.com/rdk/resource" + "go.viam.com/rdk/rimage" + tu "go.viam.com/rdk/testutils" + "go.viam.com/rdk/testutils/inject" + "go.viam.com/rdk/utils" +) + +//nolint:lll +var viamLogoJpegB64 = []byte("/9j/4QD4RXhpZgAATU0AKgAAAAgABwESAAMAAAABAAEAAAEaAAUAAAABAAAAYgEbAAUAAAABAAAAagEoAAMAAAABAAIAAAExAAIAAAAhAAAAcgITAAMAAAABAAEAAIdpAAQAAAABAAAAlAAAAAAAAABIAAAAAQAAAEgAAAABQWRvYmUgUGhvdG9zaG9wIDIzLjQgKE1hY2ludG9zaCkAAAAHkAAABwAAAAQwMjIxkQEABwAAAAQBAgMAoAAABwAAAAQwMTAwoAEAAwAAAAEAAQAAoAIABAAAAAEAAAAgoAMABAAAAAEAAAAgpAYAAwAAAAEAAAAAAAAAAAAA/9sAhAAcHBwcHBwwHBwwRDAwMERcRERERFx0XFxcXFx0jHR0dHR0dIyMjIyMjIyMqKioqKioxMTExMTc3Nzc3Nzc3NzcASIkJDg0OGA0NGDmnICc5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ub/3QAEAAL/wAARCAAgACADASIAAhEBAxEB/8QBogAAAQUBAQEBAQEAAAAAAAAAAAECAwQFBgcICQoLEAACAQMDAgQDBQUEBAAAAX0BAgMABBEFEiExQQYTUWEHInEUMoGRoQgjQrHBFVLR8CQzYnKCCQoWFxgZGiUmJygpKjQ1Njc4OTpDREVGR0hJSlNUVVZXWFlaY2RlZmdoaWpzdHV2d3h5eoOEhYaHiImKkpOUlZaXmJmaoqOkpaanqKmqsrO0tba3uLm6wsPExcbHyMnK0tPU1dbX2Nna4eLj5OXm5+jp6vHy8/T19vf4+foBAAMBAQEBAQEBAQEAAAAAAAABAgMEBQYHCAkKCxEAAgECBAQDBAcFBAQAAQJ3AAECAxEEBSExBhJBUQdhcRMiMoEIFEKRobHBCSMzUvAVYnLRChYkNOEl8RcYGRomJygpKjU2Nzg5OkNERUZHSElKU1RVVldYWVpjZGVmZ2hpanN0dXZ3eHl6goOEhYaHiImKkpOUlZaXmJmaoqOkpaanqKmqsrO0tba3uLm6wsPExcbHyMnK0tPU1dbX2Nna4uPk5ebn6Onq8vP09fb3+Pn6/9oADAMBAAIRAxEAPwDm6K0dNu1tZsSgGNuDx0961NX09WT7ZbgcD5gPT1oA5qiul0fT1VPtlwByPlB7D1rL1K7W5mxEAI04GBjPvQB//9Dm66TRr/I+xTf8A/wrm6ASpBXgjpQB0ms34UfYof8AgWP5VzdBJY5PJNFAH//Z") + +const ( + serviceName = "camera" + captureInterval = time.Millisecond +) + +func convertStringMapToAnyPBMap(params map[string]string) (map[string]*anypb.Any, error) { + methodParams := map[string]*anypb.Any{} + for key, paramVal := range params { + anyVal, err := convertStringToAnyPB(paramVal) + if err != nil { + return nil, err + } + methodParams[key] = anyVal + } + return methodParams, nil +} + +func convertStringToAnyPB(str string) (*anypb.Any, error) { + var wrappedVal protoreflect.ProtoMessage + if boolVal, err := strconv.ParseBool(str); err == nil { + wrappedVal = wrapperspb.Bool(boolVal) + } else if int64Val, err := strconv.ParseInt(str, 10, 64); err == nil { + wrappedVal = wrapperspb.Int64(int64Val) + } else if uint64Val, err := strconv.ParseUint(str, 10, 64); err == nil { + wrappedVal = wrapperspb.UInt64(uint64Val) + } else if float64Val, err := strconv.ParseFloat(str, 64); err == nil { + wrappedVal = wrapperspb.Double(float64Val) + } else { + wrappedVal = wrapperspb.String(str) + } + anyVal, err := anypb.New(wrappedVal) + if err != nil { + return nil, err + } + return anyVal, nil +} + +func TestCollectors(t *testing.T) { + logger := logging.NewTestLogger(t) + methodParams, err := convertStringMapToAnyPBMap(map[string]string{"camera_name": "camera-1", "mime_type": "image/jpeg"}) + test.That(t, err, test.ShouldBeNil) + viamLogoJpeg, err := io.ReadAll(base64.NewDecoder(base64.StdEncoding, bytes.NewReader(viamLogoJpegB64))) + test.That(t, err, test.ShouldBeNil) + viamLogoJpegAsInts := []any{} + for _, b := range viamLogoJpeg { + viamLogoJpegAsInts = append(viamLogoJpegAsInts, int(b)) + } + + img := rimage.NewLazyEncodedImage(viamLogoJpeg, utils.MimeTypeJPEG) + // 32 x 32 image + test.That(t, img.Bounds().Dx(), test.ShouldEqual, 32) + test.That(t, img.Bounds().Dy(), test.ShouldEqual, 32) + + pcd, err := pointcloud.NewFromFile(artifact.MustPath("pointcloud/test.las"), logger) + test.That(t, err, test.ShouldBeNil) + + var pcdBuf bytes.Buffer + test.That(t, pointcloud.ToPCD(pcd, &pcdBuf, pointcloud.PCDBinary), test.ShouldBeNil) + + now := time.Now() + nowPB := timestamppb.New(now) + cam := newCamera(img, img, now, pcd) + + tests := []struct { + name string + collector data.CollectorConstructor + expected *datasyncpb.SensorData + camera camera.Camera + }{ + { + name: "ReadImage returns a non nil binary response", + collector: camera.NewReadImageCollector, + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Binary{Binary: viamLogoJpeg}, + }, + camera: cam, + }, + { + name: "NextPointCloud returns a non nil binary response", + collector: camera.NewNextPointCloudCollector, + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Binary{Binary: pcdBuf.Bytes()}, + }, + camera: cam, + }, + { + name: "GetImages returns a non nil tabular response", + collector: camera.NewGetImagesCollector, + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "response_metadata": map[string]any{ + "captured_at": map[string]any{ + "seconds": nowPB.Seconds, + "nanos": nowPB.Nanos, + }, + }, + "images": []any{ + map[string]any{ + "source_name": "left", + "format": int(camerapb.Format_FORMAT_JPEG), + "image": viamLogoJpegAsInts, + }, + map[string]any{ + "source_name": "right", + "format": int(camerapb.Format_FORMAT_JPEG), + "image": viamLogoJpegAsInts, + }, + }, + })}, + }, + camera: cam, + }, + } + + for _, tc := range tests { + t.Run(tc.name, func(t *testing.T) { + start := time.Now() + buf := tu.NewMockBuffer() + params := data.CollectorParams{ + ComponentName: serviceName, + Interval: captureInterval, + Logger: logging.NewTestLogger(t), + Clock: clock.New(), + Target: buf, + MethodParams: methodParams, + } + + col, err := tc.collector(tc.camera, params) + test.That(t, err, test.ShouldBeNil) + + defer col.Close() + col.Collect() + + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() + }) + } +} + +func newCamera( + left, right image.Image, + capturedAt time.Time, + pcd pointcloud.PointCloud, +) camera.Camera { + v := &inject.Camera{} + v.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { + return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { + return left, func() {}, nil + })), nil + } + + v.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { + return pcd, nil + } + + v.ImagesFunc = func(ctx context.Context) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{ + {Image: left, SourceName: "left"}, + {Image: right, SourceName: "right"}, + }, + resource.ResponseMetadata{CapturedAt: capturedAt}, + nil + } + + return v +} diff --git a/components/camera/export_collectors_test.go b/components/camera/export_collectors_test.go new file mode 100644 index 00000000000..b6692840298 --- /dev/null +++ b/components/camera/export_collectors_test.go @@ -0,0 +1,10 @@ +package camera + +// export_collectors_test.go adds functionality to the package that we only want to use and expose during testing. + +// Exported variables for testing collectors, see unexported collectors for implementation details. +var ( + NewNextPointCloudCollector = newNextPointCloudCollector + NewReadImageCollector = newReadImageCollector + NewGetImagesCollector = newGetImagesCollector +) diff --git a/components/encoder/collector.go b/components/encoder/collectors.go similarity index 100% rename from components/encoder/collector.go rename to components/encoder/collectors.go diff --git a/components/encoder/collectors_test.go b/components/encoder/collectors_test.go index 05e1de16532..d24e719a860 100644 --- a/components/encoder/collectors_test.go +++ b/components/encoder/collectors_test.go @@ -5,7 +5,8 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" pb "go.viam.com/api/component/encoder/v1" "go.viam.com/test" @@ -17,19 +18,18 @@ import ( ) const ( - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) -func TestEncoderCollector(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} +func TestCollectors(t *testing.T) { + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: "encoder", Interval: captureInterval, Logger: logging.NewTestLogger(t), - Target: &buf, - Clock: mockClock, + Target: buf, + Clock: clock.New(), } enc := newEncoder() @@ -38,18 +38,17 @@ func TestEncoderCollector(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, - tu.ToProtoMapIgnoreOmitEmpty(pb.GetPositionResponse{ - Value: 1.0, - PositionType: pb.PositionType_POSITION_TYPE_TICKS_COUNT, - })) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "value": 1.0, + "position_type": int(pb.PositionType_POSITION_TYPE_TICKS_COUNT), + })}, + }) + buf.Close() } func newEncoder() encoder.Encoder { diff --git a/components/gantry/collector.go b/components/gantry/collectors.go similarity index 100% rename from components/gantry/collector.go rename to components/gantry/collectors.go diff --git a/components/gantry/collectors_test.go b/components/gantry/collectors_test.go index c450b0fbbea..1080fe7abc1 100644 --- a/components/gantry/collectors_test.go +++ b/components/gantry/collectors_test.go @@ -5,8 +5,8 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" - pb "go.viam.com/api/component/gantry/v1" + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" "go.viam.com/test" "go.viam.com/rdk/components/gantry" @@ -18,45 +18,50 @@ import ( const ( componentName = "gantry" - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) // floatList is a lit of floats in units of millimeters. var floatList = []float64{1000, 2000, 3000} -func TestGantryCollectors(t *testing.T) { +func TestCollectors(t *testing.T) { tests := []struct { name string collector data.CollectorConstructor - expected map[string]any + expected *datasyncpb.SensorData }{ { name: "Length collector should write a lengths response", collector: gantry.NewLengthsCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetLengthsResponse{ - LengthsMm: floatList, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "lengths_mm": []any{1000, 2000, 3000}, + })}, + }, }, { name: "Position collector should write a list of positions", collector: gantry.NewPositionCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetPositionResponse{ - PositionsMm: floatList, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "positions_mm": []any{1000, 2000, 3000}, + })}, + }, }, } for _, tc := range tests { t.Run(tc.name, func(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: componentName, Interval: captureInterval, Logger: logging.NewTestLogger(t), - Clock: mockClock, - Target: &buf, + Clock: clock.New(), + Target: buf, } gantry := newGantry() @@ -65,13 +70,11 @@ func TestGantryCollectors(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, tc.expected) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() }) } } diff --git a/components/motor/collector.go b/components/motor/collectors.go similarity index 100% rename from components/motor/collector.go rename to components/motor/collectors.go diff --git a/components/motor/collectors_test.go b/components/motor/collectors_test.go index f80baf75095..8b5444d8909 100644 --- a/components/motor/collectors_test.go +++ b/components/motor/collectors_test.go @@ -5,8 +5,8 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" - pb "go.viam.com/api/component/motor/v1" + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" "go.viam.com/test" "go.viam.com/rdk/components/motor" @@ -18,43 +18,48 @@ import ( const ( componentName = "motor" - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) -func TestMotorCollectors(t *testing.T) { +func TestCollectors(t *testing.T) { tests := []struct { name string collector data.CollectorConstructor - expected map[string]any + expected *datasyncpb.SensorData }{ { name: "Motor position collector should write a position response", collector: motor.NewPositionCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetPositionResponse{ - Position: 1.0, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "position": 1.0, + })}, + }, }, { name: "Motor isPowered collector should write an isPowered response", collector: motor.NewIsPoweredCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.IsPoweredResponse{ - IsOn: false, - PowerPct: .5, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "is_on": false, + "power_pct": 0.5, + })}, + }, }, } for _, tc := range tests { t.Run(tc.name, func(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: componentName, Interval: captureInterval, Logger: logging.NewTestLogger(t), - Clock: mockClock, - Target: &buf, + Clock: clock.New(), + Target: buf, } motor := newMotor() @@ -63,13 +68,11 @@ func TestMotorCollectors(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, tc.expected) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() }) } } diff --git a/components/movementsensor/collector.go b/components/movementsensor/collectors.go similarity index 100% rename from components/movementsensor/collector.go rename to components/movementsensor/collectors.go diff --git a/components/movementsensor/collectors_test.go b/components/movementsensor/collectors_test.go index 38b77e21526..f87c21ba99d 100644 --- a/components/movementsensor/collectors_test.go +++ b/components/movementsensor/collectors_test.go @@ -5,16 +5,14 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" + "github.com/benbjohnson/clock" "github.com/golang/geo/r3" geo "github.com/kellydunn/golang-geo" - v1 "go.viam.com/api/common/v1" - pb "go.viam.com/api/component/movementsensor/v1" + datasyncpb "go.viam.com/api/app/datasync/v1" "go.viam.com/test" "go.viam.com/rdk/components/movementsensor" "go.viam.com/rdk/data" - du "go.viam.com/rdk/data/testutils" "go.viam.com/rdk/logging" "go.viam.com/rdk/spatialmath" tu "go.viam.com/rdk/testutils" @@ -23,8 +21,7 @@ import ( const ( componentName = "movementsensor" - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) var vec = r3.Vector{ @@ -35,75 +32,118 @@ var vec = r3.Vector{ var readingMap = map[string]any{"reading1": false, "reading2": "test"} -func TestMovementSensorCollectors(t *testing.T) { +func TestCollectors(t *testing.T) { tests := []struct { name string collector data.CollectorConstructor - expected map[string]any + expected *datasyncpb.SensorData }{ { name: "Movement sensor linear velocity collector should write a velocity response", collector: movementsensor.NewLinearVelocityCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetLinearVelocityResponse{ - LinearVelocity: r3VectorToV1Vector(vec), - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "linear_velocity": map[string]any{ + "x": 1.0, + "y": 2.0, + "z": 3.0, + }, + })}, + }, }, { name: "Movement sensor position collector should write a position response", collector: movementsensor.NewPositionCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetPositionResponse{ - Coordinate: &v1.GeoPoint{ - Latitude: 1.0, - Longitude: 2.0, - }, - AltitudeM: 3.0, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "coordinate": map[string]any{ + "latitude": 1.0, + "longitude": 2.0, + }, + "altitude_m": 3.0, + })}, + }, }, { name: "Movement sensor angular velocity collector should write a velocity response", collector: movementsensor.NewAngularVelocityCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetAngularVelocityResponse{ - AngularVelocity: r3VectorToV1Vector(vec), - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "angular_velocity": map[string]any{ + "x": 1.0, + "y": 2.0, + "z": 3.0, + }, + })}, + }, }, { name: "Movement sensor compass heading collector should write a heading response", collector: movementsensor.NewCompassHeadingCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetCompassHeadingResponse{ - Value: 1.0, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "value": 1.0, + })}, + }, }, { name: "Movement sensor linear acceleration collector should write an acceleration response", collector: movementsensor.NewLinearAccelerationCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetLinearAccelerationResponse{ - LinearAcceleration: r3VectorToV1Vector(vec), - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "linear_acceleration": map[string]any{ + "x": 1.0, + "y": 2.0, + "z": 3.0, + }, + })}, + }, }, { name: "Movement sensor orientation collector should write an orientation response", collector: movementsensor.NewOrientationCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetOrientationResponse{ - Orientation: getExpectedOrientation(), - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "orientation": map[string]any{ + "o_x": 0, + "o_y": 0, + "o_z": 1, + "theta": 0, + }, + })}, + }, }, { name: "Movement sensor readings collector should write a readings response", collector: movementsensor.NewReadingsCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(du.GetExpectedReadingsStruct(readingMap).AsMap()), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "readings": map[string]any{ + "reading1": false, + "reading2": "test", + }, + })}, + }, }, } for _, tc := range tests { t.Run(tc.name, func(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: componentName, Interval: captureInterval, Logger: logging.NewTestLogger(t), - Clock: mockClock, - Target: &buf, + Clock: clock.New(), + Target: buf, } movSens := newMovementSensor() @@ -112,13 +152,11 @@ func TestMovementSensorCollectors(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, tc.expected) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() }) } } @@ -152,21 +190,3 @@ func newMovementSensor() movementsensor.MovementSensor { } return m } - -func r3VectorToV1Vector(vec r3.Vector) *v1.Vector3 { - return &v1.Vector3{ - X: vec.X, - Y: vec.Y, - Z: vec.Z, - } -} - -func getExpectedOrientation() *v1.Orientation { - convertedAngles := spatialmath.NewZeroOrientation().AxisAngles() - return &v1.Orientation{ - OX: convertedAngles.RX, - OY: convertedAngles.RY, - OZ: convertedAngles.RZ, - Theta: convertedAngles.Theta, - } -} diff --git a/components/powersensor/collector.go b/components/powersensor/collectors.go similarity index 100% rename from components/powersensor/collector.go rename to components/powersensor/collectors.go diff --git a/components/powersensor/collectors_test.go b/components/powersensor/collectors_test.go index 79dbd754738..e27aa270527 100644 --- a/components/powersensor/collectors_test.go +++ b/components/powersensor/collectors_test.go @@ -5,13 +5,12 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" - pb "go.viam.com/api/component/powersensor/v1" + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" "go.viam.com/test" "go.viam.com/rdk/components/powersensor" "go.viam.com/rdk/data" - du "go.viam.com/rdk/data/testutils" "go.viam.com/rdk/logging" tu "go.viam.com/rdk/testutils" "go.viam.com/rdk/testutils/inject" @@ -19,58 +18,74 @@ import ( const ( componentName = "powersensor" - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) var readingMap = map[string]any{"reading1": false, "reading2": "test"} -func TestPowerSensorCollectors(t *testing.T) { +func TestCollectors(t *testing.T) { tests := []struct { name string collector data.CollectorConstructor - expected map[string]any + expected *datasyncpb.SensorData }{ { name: "Power sensor voltage collector should write a voltage response", collector: powersensor.NewVoltageCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetVoltageResponse{ - Volts: 1.0, - IsAc: false, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "volts": 1.0, + "is_ac": false, + })}, + }, }, { name: "Power sensor current collector should write a current response", collector: powersensor.NewCurrentCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetCurrentResponse{ - Amperes: 1.0, - IsAc: false, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "amperes": 1.0, + "is_ac": false, + })}, + }, }, { name: "Power sensor power collector should write a power response", collector: powersensor.NewPowerCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.GetPowerResponse{ - Watts: 1.0, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "watts": 1.0, + })}, + }, }, { name: "Power sensor readings collector should write a readings response", collector: powersensor.NewReadingsCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(du.GetExpectedReadingsStruct(readingMap).AsMap()), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "readings": map[string]any{ + "reading1": false, + "reading2": "test", + }, + })}, + }, }, } for _, tc := range tests { t.Run(tc.name, func(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: componentName, Interval: captureInterval, Logger: logging.NewTestLogger(t), - Clock: mockClock, - Target: &buf, + Clock: clock.New(), + Target: buf, } pwrSens := newPowerSensor() @@ -79,13 +94,11 @@ func TestPowerSensorCollectors(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, tc.expected) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() }) } } diff --git a/components/sensor/collector.go b/components/sensor/collectors.go similarity index 100% rename from components/sensor/collector.go rename to components/sensor/collectors.go diff --git a/components/sensor/collector_test.go b/components/sensor/collectors_test.go similarity index 55% rename from components/sensor/collector_test.go rename to components/sensor/collectors_test.go index 752f256c1e3..33b6c62217b 100644 --- a/components/sensor/collector_test.go +++ b/components/sensor/collectors_test.go @@ -5,33 +5,32 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" "go.viam.com/test" "go.viam.com/rdk/components/sensor" "go.viam.com/rdk/data" - du "go.viam.com/rdk/data/testutils" "go.viam.com/rdk/logging" tu "go.viam.com/rdk/testutils" "go.viam.com/rdk/testutils/inject" ) const ( - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) var readingMap = map[string]any{"reading1": false, "reading2": "test"} -func TestSensorCollector(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} +func TestCollectors(t *testing.T) { + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: "sensor", Interval: captureInterval, Logger: logging.NewTestLogger(t), - Target: &buf, - Clock: mockClock, + Target: buf, + Clock: clock.New(), } sens := newSensor() @@ -40,13 +39,19 @@ func TestSensorCollector(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, du.GetExpectedReadingsStruct(readingMap).AsMap()) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "readings": map[string]any{ + "reading1": false, + "reading2": "test", + }, + })}, + }) + buf.Close() } func newSensor() sensor.Sensor { diff --git a/components/servo/collector.go b/components/servo/collectors.go similarity index 100% rename from components/servo/collector.go rename to components/servo/collectors.go diff --git a/components/servo/collectors_test.go b/components/servo/collectors_test.go index 6e253f730ef..0a1219d75ee 100644 --- a/components/servo/collectors_test.go +++ b/components/servo/collectors_test.go @@ -5,8 +5,8 @@ import ( "testing" "time" - clk "github.com/benbjohnson/clock" - pb "go.viam.com/api/component/servo/v1" + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" "go.viam.com/test" "go.viam.com/rdk/components/servo" @@ -17,19 +17,18 @@ import ( ) const ( - captureInterval = time.Second - numRetries = 5 + captureInterval = time.Millisecond ) -func TestServoCollector(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} +func TestCollectors(t *testing.T) { + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: "servo", Interval: captureInterval, Logger: logging.NewTestLogger(t), - Target: &buf, - Clock: mockClock, + Target: buf, + Clock: clock.New(), } serv := newServo() @@ -38,16 +37,16 @@ func TestServoCollector(t *testing.T) { defer col.Close() col.Collect() - mockClock.Add(captureInterval) - - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, - tu.ToProtoMapIgnoreOmitEmpty(pb.GetPositionResponse{ - PositionDeg: 1.0, - })) + + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "position_deg": 1.0, + })}, + }) + buf.Close() } func newServo() servo.Servo { diff --git a/services/slam/collector.go b/services/slam/collectors.go similarity index 100% rename from services/slam/collector.go rename to services/slam/collectors.go diff --git a/services/slam/collectors_test.go b/services/slam/collectors_test.go new file mode 100644 index 00000000000..b58c4ae56fb --- /dev/null +++ b/services/slam/collectors_test.go @@ -0,0 +1,125 @@ +package slam_test + +import ( + "context" + "os" + "path/filepath" + "testing" + "time" + + "github.com/benbjohnson/clock" + "github.com/golang/geo/r3" + datasyncpb "go.viam.com/api/app/datasync/v1" + "go.viam.com/test" + "go.viam.com/utils" + "go.viam.com/utils/artifact" + + "go.viam.com/rdk/data" + "go.viam.com/rdk/logging" + "go.viam.com/rdk/services/slam" + "go.viam.com/rdk/spatialmath" + tu "go.viam.com/rdk/testutils" + "go.viam.com/rdk/testutils/inject" +) + +const ( + serviceName = "slam" + captureInterval = time.Millisecond +) + +func TestCollectors(t *testing.T) { + pcdPath := filepath.Clean(artifact.MustPath("pointcloud/octagonspace.pcd")) + pcd, err := os.ReadFile(pcdPath) + test.That(t, err, test.ShouldBeNil) + tests := []struct { + name string + collector data.CollectorConstructor + expected *datasyncpb.SensorData + slam slam.Service + }{ + { + name: "PositionCollector returns non-empty position responses", + collector: slam.NewPositionCollector, + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "pose": map[string]any{ + "o_x": 0, + "o_y": 0, + "o_z": 1, + "theta": 0, + "x": 1, + "y": 2, + "z": 3, + }, + })}, + }, + slam: newSlamService(pcdPath), + }, + { + name: "PointCloudMapCollector returns non-empty pointcloud responses", + collector: slam.NewPointCloudMapCollector, + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Binary{Binary: pcd}, + }, + slam: newSlamService(pcdPath), + }, + } + + for _, tc := range tests { + t.Run(tc.name, func(t *testing.T) { + start := time.Now() + buf := tu.NewMockBuffer() + params := data.CollectorParams{ + ComponentName: serviceName, + Interval: captureInterval, + Logger: logging.NewTestLogger(t), + Clock: clock.New(), + Target: buf, + } + + col, err := tc.collector(tc.slam, params) + test.That(t, err, test.ShouldBeNil) + + defer col.Close() + col.Collect() + + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() + }) + } +} + +func getPointCloudMap(path string) (func() ([]byte, error), error) { + const chunkSizeBytes = 1 * 1024 * 1024 + file, err := os.Open(path) + if err != nil { + return nil, err + } + chunk := make([]byte, chunkSizeBytes) + f := func() ([]byte, error) { + bytesRead, err := file.Read(chunk) + if err != nil { + defer utils.UncheckedErrorFunc(file.Close) + return nil, err + } + return chunk[:bytesRead], err + } + return f, nil +} + +func newSlamService(pcdPath string) slam.Service { + v := &inject.SLAMService{} + v.PositionFunc = func(ctx context.Context) (spatialmath.Pose, error) { + return spatialmath.NewPoseFromPoint(r3.Vector{X: 1, Y: 2, Z: 3}), nil + } + + v.PointCloudMapFunc = func(ctx context.Context, returnEditedMap bool) (func() ([]byte, error), error) { + return getPointCloudMap(pcdPath) + } + + return v +} diff --git a/services/slam/export_collectors_test.go b/services/slam/export_collectors_test.go new file mode 100644 index 00000000000..b8b27d261c0 --- /dev/null +++ b/services/slam/export_collectors_test.go @@ -0,0 +1,9 @@ +package slam + +// export_collectors_test.go adds functionality to the package that we only want to use and expose during testing. + +// Exported variables for testing collectors, see unexported collectors for implementation details. +var ( + NewPointCloudMapCollector = newPointCloudMapCollector + NewPositionCollector = newPositionCollector +) diff --git a/services/vision/collector.go b/services/vision/collectors.go similarity index 100% rename from services/vision/collector.go rename to services/vision/collectors.go diff --git a/services/vision/collectors_test.go b/services/vision/collectors_test.go index 1c05a93c5c0..f9cac5e0d35 100644 --- a/services/vision/collectors_test.go +++ b/services/vision/collectors_test.go @@ -1,33 +1,38 @@ package vision_test import ( + "bytes" "context" + "encoding/base64" "image" + "io" "strconv" "testing" "time" - clk "github.com/benbjohnson/clock" - v1 "go.viam.com/api/common/v1" + "github.com/benbjohnson/clock" + datasyncpb "go.viam.com/api/app/datasync/v1" camerapb "go.viam.com/api/component/camera/v1" - pb "go.viam.com/api/service/vision/v1" "go.viam.com/test" - "go.viam.com/utils/protoutils" "google.golang.org/protobuf/reflect/protoreflect" "google.golang.org/protobuf/types/known/anypb" "google.golang.org/protobuf/types/known/wrapperspb" "go.viam.com/rdk/data" "go.viam.com/rdk/logging" + "go.viam.com/rdk/rimage" visionservice "go.viam.com/rdk/services/vision" tu "go.viam.com/rdk/testutils" "go.viam.com/rdk/testutils/inject" - vision "go.viam.com/rdk/vision" + "go.viam.com/rdk/utils" "go.viam.com/rdk/vision/classification" "go.viam.com/rdk/vision/objectdetection" "go.viam.com/rdk/vision/viscapture" ) +//nolint:lll +var viamLogoJpegB64 = []byte("/9j/4QD4RXhpZgAATU0AKgAAAAgABwESAAMAAAABAAEAAAEaAAUAAAABAAAAYgEbAAUAAAABAAAAagEoAAMAAAABAAIAAAExAAIAAAAhAAAAcgITAAMAAAABAAEAAIdpAAQAAAABAAAAlAAAAAAAAABIAAAAAQAAAEgAAAABQWRvYmUgUGhvdG9zaG9wIDIzLjQgKE1hY2ludG9zaCkAAAAHkAAABwAAAAQwMjIxkQEABwAAAAQBAgMAoAAABwAAAAQwMTAwoAEAAwAAAAEAAQAAoAIABAAAAAEAAAAgoAMABAAAAAEAAAAgpAYAAwAAAAEAAAAAAAAAAAAA/9sAhAAcHBwcHBwwHBwwRDAwMERcRERERFx0XFxcXFx0jHR0dHR0dIyMjIyMjIyMqKioqKioxMTExMTc3Nzc3Nzc3NzcASIkJDg0OGA0NGDmnICc5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ubm5ub/3QAEAAL/wAARCAAgACADASIAAhEBAxEB/8QBogAAAQUBAQEBAQEAAAAAAAAAAAECAwQFBgcICQoLEAACAQMDAgQDBQUEBAAAAX0BAgMABBEFEiExQQYTUWEHInEUMoGRoQgjQrHBFVLR8CQzYnKCCQoWFxgZGiUmJygpKjQ1Njc4OTpDREVGR0hJSlNUVVZXWFlaY2RlZmdoaWpzdHV2d3h5eoOEhYaHiImKkpOUlZaXmJmaoqOkpaanqKmqsrO0tba3uLm6wsPExcbHyMnK0tPU1dbX2Nna4eLj5OXm5+jp6vHy8/T19vf4+foBAAMBAQEBAQEBAQEAAAAAAAABAgMEBQYHCAkKCxEAAgECBAQDBAcFBAQAAQJ3AAECAxEEBSExBhJBUQdhcRMiMoEIFEKRobHBCSMzUvAVYnLRChYkNOEl8RcYGRomJygpKjU2Nzg5OkNERUZHSElKU1RVVldYWVpjZGVmZ2hpanN0dXZ3eHl6goOEhYaHiImKkpOUlZaXmJmaoqOkpaanqKmqsrO0tba3uLm6wsPExcbHyMnK0tPU1dbX2Nna4uPk5ebn6Onq8vP09fb3+Pn6/9oADAMBAAIRAxEAPwDm6K0dNu1tZsSgGNuDx0961NX09WT7ZbgcD5gPT1oA5qiul0fT1VPtlwByPlB7D1rL1K7W5mxEAI04GBjPvQB//9Dm66TRr/I+xTf8A/wrm6ASpBXgjpQB0ms34UfYof8AgWP5VzdBJY5PJNFAH//Z") + type fakeDetection struct { boundingBox *image.Rectangle score float64 @@ -39,18 +44,9 @@ type fakeClassification struct { label string } -type extraFields struct { - Height int - Width int - MimeType string -} - const ( serviceName = "vision" - captureInterval = time.Second - numRetries = 5 - testName1 = "CaptureAllFromCameraCollector returns non-empty CaptureAllFromCameraResp" - testName2 = "CaptureAllFromCameraCollector w/ Classifications & Detections < 0.5 returns empty CaptureAllFromCameraResp" + captureInterval = time.Millisecond ) var fakeDetections = []objectdetection.Detection{ @@ -77,7 +73,7 @@ var fakeDetections2 = []objectdetection.Detection{ var fakeClassifications = []classification.Classification{ &fakeClassification{ - score: 0.95, + score: 0.85, label: "cat", }, } @@ -89,12 +85,6 @@ var fakeClassifications2 = []classification.Classification{ }, } -var fakeObjects = []*vision.Object{} - -var extra = extraFields{} - -var fakeExtraFields, _ = protoutils.StructToStructPb(extra) - func (fc *fakeClassification) Score() float64 { return fc.score } @@ -115,42 +105,6 @@ func (fd *fakeDetection) Label() string { return fd.label } -func clasToProto(classifications classification.Classifications) []*pb.Classification { - protoCs := make([]*pb.Classification, 0, len(classifications)) - for _, c := range classifications { - cc := &pb.Classification{ - ClassName: c.Label(), - Confidence: c.Score(), - } - protoCs = append(protoCs, cc) - } - return protoCs -} - -func detsToProto(detections []objectdetection.Detection) []*pb.Detection { - protoDets := make([]*pb.Detection, 0, len(detections)) - for _, det := range detections { - box := det.BoundingBox() - if box == nil { - return nil - } - xMin := int64(box.Min.X) - yMin := int64(box.Min.Y) - xMax := int64(box.Max.X) - yMax := int64(box.Max.Y) - d := &pb.Detection{ - XMin: &xMin, - YMin: &yMin, - XMax: &xMax, - YMax: &yMax, - Confidence: det.Score(), - ClassName: det.Label(), - } - protoDets = append(protoDets, d) - } - return protoDets -} - func convertStringMapToAnyPBMap(params map[string]string) (map[string]*anypb.Any, error) { methodParams := map[string]*anypb.Any{} for key, paramVal := range params { @@ -183,100 +137,168 @@ func convertStringToAnyPB(str string) (*anypb.Any, error) { return anyVal, nil } -var methodParams, _ = convertStringMapToAnyPBMap(map[string]string{"camera_name": "camera-1", "mime_type": "image/jpeg"}) - func TestCollectors(t *testing.T) { + methodParams, err := convertStringMapToAnyPBMap(map[string]string{"camera_name": "camera-1", "mime_type": "image/jpeg"}) + test.That(t, err, test.ShouldBeNil) + viamLogoJpeg, err := io.ReadAll(base64.NewDecoder(base64.StdEncoding, bytes.NewReader(viamLogoJpegB64))) + test.That(t, err, test.ShouldBeNil) + viamLogoJpegAsInts := []any{} + for _, b := range viamLogoJpeg { + viamLogoJpegAsInts = append(viamLogoJpegAsInts, int(b)) + } + + img := rimage.NewLazyEncodedImage(viamLogoJpeg, utils.MimeTypeJPEG) + // 32 x 32 image + test.That(t, img.Bounds().Dx(), test.ShouldEqual, 32) + test.That(t, img.Bounds().Dy(), test.ShouldEqual, 32) + tests := []struct { name string collector data.CollectorConstructor - expected map[string]any + expected *datasyncpb.SensorData + vision visionservice.Service }{ { - name: testName1, + name: "CaptureAllFromCameraCollector returns non-empty CaptureAllFromCameraResp", collector: visionservice.NewCaptureAllFromCameraCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.CaptureAllFromCameraResponse{ - Image: &camerapb.Image{}, - Classifications: clasToProto(fakeClassifications), - Detections: detsToProto(fakeDetections), - Objects: []*v1.PointCloudObject{}, - Extra: fakeExtraFields, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "image": map[string]any{ + "source_name": "camera-1", + "format": int(camerapb.Format_FORMAT_JPEG), + "image": viamLogoJpegAsInts, + }, + "classifications": []any{ + map[string]any{ + "confidence": 0.85, + "class_name": "cat", + }, + }, + "detections": []any{ + map[string]any{ + "confidence": 0.95, + "class_name": "cat", + "x_min": 10, + "y_min": 20, + "x_max": 110, + "y_max": 120, + }, + }, + "objects": []any{}, + "extra": map[string]any{ + "fields": map[string]any{ + "Height": map[string]any{ + "Kind": map[string]any{ + "NumberValue": 32, + }, + }, + "Width": map[string]any{ + "Kind": map[string]any{ + "NumberValue": 32, + }, + }, + "MimeType": map[string]any{ + "Kind": map[string]any{ + "StringValue": utils.MimeTypeJPEG, + }, + }, + }, + }, + })}, + }, + vision: newVisionService(img), }, { - name: testName2, + name: "CaptureAllFromCameraCollector w/ Classifications & Detections < 0.5 returns empty CaptureAllFromCameraResp", collector: visionservice.NewCaptureAllFromCameraCollector, - expected: tu.ToProtoMapIgnoreOmitEmpty(pb.CaptureAllFromCameraResponse{ - Image: &camerapb.Image{}, - Classifications: clasToProto([]classification.Classification{}), - Detections: detsToProto([]objectdetection.Detection{}), - Objects: []*v1.PointCloudObject{}, - Extra: fakeExtraFields, - }), + expected: &datasyncpb.SensorData{ + Metadata: &datasyncpb.SensorMetadata{}, + Data: &datasyncpb.SensorData_Struct{Struct: tu.ToStructPBStruct(t, map[string]any{ + "image": map[string]any{ + "source_name": "camera-1", + "format": 3, + "image": viamLogoJpegAsInts, + }, + "classifications": []any{}, + "detections": []any{}, + "objects": []any{}, + "extra": map[string]any{ + "fields": map[string]any{ + "Height": map[string]any{ + "Kind": map[string]any{ + "NumberValue": 32, + }, + }, + "Width": map[string]any{ + "Kind": map[string]any{ + "NumberValue": 32, + }, + }, + "MimeType": map[string]any{ + "Kind": map[string]any{ + "StringValue": utils.MimeTypeJPEG, + }, + }, + }, + }, + })}, + }, + vision: newVisionService2(img), }, } for _, tc := range tests { t.Run(tc.name, func(t *testing.T) { - mockClock := clk.NewMock() - buf := tu.MockBuffer{} + start := time.Now() + buf := tu.NewMockBuffer() params := data.CollectorParams{ ComponentName: serviceName, Interval: captureInterval, Logger: logging.NewTestLogger(t), - Clock: mockClock, - Target: &buf, + Clock: clock.New(), + Target: buf, MethodParams: methodParams, } - var vision visionservice.Service - if tc.name == testName1 { - vision = newVisionService() - } else if tc.name == testName2 { - vision = newVisionService2() - } - - col, err := tc.collector(vision, params) + col, err := tc.collector(tc.vision, params) test.That(t, err, test.ShouldBeNil) defer col.Close() col.Collect() - mockClock.Add(captureInterval) - tu.Retry(func() bool { - return buf.Length() != 0 - }, numRetries) - test.That(t, buf.Length(), test.ShouldBeGreaterThan, 0) - test.That(t, buf.Writes[0].GetStruct().AsMap(), test.ShouldResemble, tc.expected) + ctx, cancel := context.WithTimeout(context.Background(), time.Second) + defer cancel() + tu.CheckMockBufferWrites(t, ctx, start, buf.Writes, tc.expected) + buf.Close() }) } } -func newVisionService() visionservice.Service { +func newVisionService(img image.Image) visionservice.Service { v := &inject.VisionService{} v.CaptureAllFromCameraFunc = func(ctx context.Context, cameraName string, opts viscapture.CaptureOptions, extra map[string]interface{}, ) (viscapture.VisCapture, error) { return viscapture.VisCapture{ - Image: nil, + Image: img, Detections: fakeDetections, Classifications: fakeClassifications, - Objects: fakeObjects, }, nil } return v } -func newVisionService2() visionservice.Service { +func newVisionService2(img image.Image) visionservice.Service { v := &inject.VisionService{} v.CaptureAllFromCameraFunc = func(ctx context.Context, cameraName string, opts viscapture.CaptureOptions, extra map[string]interface{}, ) (viscapture.VisCapture, error) { return viscapture.VisCapture{ - Image: nil, + Image: img, Detections: fakeDetections2, Classifications: fakeClassifications2, - Objects: fakeObjects, }, nil } diff --git a/testutils/file_utils.go b/testutils/file_utils.go index f6fbe4252cf..ece95ec9d40 100644 --- a/testutils/file_utils.go +++ b/testutils/file_utils.go @@ -1,16 +1,19 @@ package testutils import ( + "context" "errors" "io" "os" "os/exec" "path/filepath" "runtime" - "sync" "testing" + "time" v1 "go.viam.com/api/app/datasync/v1" + "go.viam.com/test" + "google.golang.org/protobuf/types/known/structpb" "go.viam.com/rdk/utils" ) @@ -100,22 +103,96 @@ func BuildTempModuleWithFirstRun(tb testing.TB, modDir string) string { // MockBuffer is a buffered writer that just appends data to an array to read // without needing a real file system for testing. type MockBuffer struct { - lock sync.Mutex - Writes []*v1.SensorData + ctx context.Context + cancel context.CancelFunc + Writes chan *v1.SensorData } -// Write adds a collected sensor reading to the array. +// NewMockBuffer returns a mock buffer. +// This needs to be closed before the collector, otherwise the +// collector's Close method will block. +func NewMockBuffer() *MockBuffer { + c, cancel := context.WithCancel(context.Background()) + return &MockBuffer{ + ctx: c, + cancel: cancel, + Writes: make(chan *v1.SensorData, 1), + } +} + +// ToStructPBStruct calls structpb.NewValue and fails tests if an error +// is encountered. +// Otherwise, returns a *structpb.Struct. +func ToStructPBStruct(t *testing.T, v any) *structpb.Struct { + s, err := structpb.NewValue(v) + test.That(t, err, test.ShouldBeNil) + return s.GetStructValue() +} + +func isBinary(item *v1.SensorData) bool { + if item == nil { + return false + } + switch item.Data.(type) { + case *v1.SensorData_Binary: + return true + default: + return false + } +} + +// CheckMockBufferWrites checks that the Write +// match the expected data & metadata (timestamps). +func CheckMockBufferWrites( + t *testing.T, + ctx context.Context, + start time.Time, + writes chan *v1.SensorData, + expected *v1.SensorData, +) { + select { + case <-ctx.Done(): + t.Error("timeout") + t.FailNow() + case write := <-writes: + end := time.Now() + // nil out to make comparable + requestedAt := write.Metadata.TimeRequested.AsTime() + receivedAt := write.Metadata.TimeReceived.AsTime() + test.That(t, start, test.ShouldHappenOnOrBefore, requestedAt) + test.That(t, requestedAt, test.ShouldHappenOnOrBefore, receivedAt) + test.That(t, receivedAt, test.ShouldHappenOnOrBefore, end) + // nil out to make comparable + write.Metadata.TimeRequested = nil + write.Metadata.TimeReceived = nil + test.That(t, write.GetMetadata(), test.ShouldResemble, expected.GetMetadata()) + if isBinary(write) { + test.That(t, write.GetBinary(), test.ShouldResemble, expected.GetBinary()) + } else { + test.That(t, write.GetStruct(), test.ShouldResemble, expected.GetStruct()) + } + } +} + +// Close cancels the MockBuffer context so all methods stop blocking. +func (m *MockBuffer) Close() { + m.cancel() +} + +// Write adds the item to the channel. func (m *MockBuffer) Write(item *v1.SensorData) error { - m.lock.Lock() - defer m.lock.Unlock() - m.Writes = append(m.Writes, item) + if err := m.ctx.Err(); err != nil { + return err + } + select { + case m.Writes <- item: + case <-m.ctx.Done(): + } return nil } // Flush does nothing in this implementation as all data will be stored in memory. func (m *MockBuffer) Flush() error { - m.lock.Lock() - defer m.lock.Unlock() return nil } @@ -123,10 +200,3 @@ func (m *MockBuffer) Flush() error { func (m *MockBuffer) Path() string { return "/mock/dir" } - -// Length gets the length of the buffer without race conditions. -func (m *MockBuffer) Length() int { - m.lock.Lock() - defer m.lock.Unlock() - return len(m.Writes) -} From d63980e34beba4aae537234e45fa4d92f6bfe45b Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 14:42:27 -0500 Subject: [PATCH 44/51] Fix new collector tests --- components/camera/collectors_test.go | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/components/camera/collectors_test.go b/components/camera/collectors_test.go index 60af3460585..e4d7e23983a 100644 --- a/components/camera/collectors_test.go +++ b/components/camera/collectors_test.go @@ -22,7 +22,6 @@ import ( "go.viam.com/rdk/components/camera" "go.viam.com/rdk/data" - "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" @@ -185,10 +184,12 @@ func newCamera( pcd pointcloud.PointCloud, ) camera.Camera { v := &inject.Camera{} - v.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) { - return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - return left, func() {}, nil - })), nil + v.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + resBytes, err := rimage.EncodeImage(ctx, left, mimeType) + if err != nil { + return nil, camera.ImageMetadata{}, err + } + return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil } v.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { From 6ffbae245c0a086d49a124b9d6fa629137288be4 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 15:29:58 -0500 Subject: [PATCH 45/51] Change image.Image getter wrapper to take in a camera resource not a soon to be deprecated VideoSource --- components/camera/camera.go | 4 ++-- components/camera/camera_test.go | 25 ++++++++++++++--------- components/camera/client.go | 2 +- components/camera/client_test.go | 10 ++++----- components/camera/collectors_test.go | 4 ++-- components/camera/fake/camera_test.go | 2 +- components/camera/fake/image_file_test.go | 2 +- robot/client/client_test.go | 2 +- robot/impl/local_robot_test.go | 2 +- 9 files changed, 29 insertions(+), 24 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 2c946f4e2fb..1c6732f45a9 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -159,8 +159,8 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func return gostream.ReadImage(ctx, src) } -// ImageFromVideoSource retrieves image bytes from a camera source and decodes it into an image.Image type. -func ImageFromVideoSource(ctx context.Context, mimeType string, extra map[string]interface{}, cam VideoSource) (image.Image, error) { +// GoImageFromCamera retrieves image bytes from a camera resource and serializes it as an image.Image. +func GoImageFromCamera(ctx context.Context, mimeType string, extra map[string]interface{}, cam Camera) (image.Image, error) { resBytes, resMetadata, err := cam.Image(ctx, mimeType, extra) if err != nil { return nil, fmt.Errorf("could not get image bytes from camera: %w", err) diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index fcaec46e208..23a6f44ab0d 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -10,6 +10,7 @@ import ( "go.viam.com/utils/artifact" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -167,6 +168,7 @@ func (cs *cloudSource) NextPointCloud(ctx context.Context) (pointcloud.PointClou } func TestCameraWithNoProjector(t *testing.T) { + logger := logging.NewTestLogger(t) videoSrc := &simpleSource{"rimage/board1"} noProj, err := camera.NewVideoSourceFromReader(context.Background(), videoSrc, nil, camera.DepthStream) test.That(t, err, test.ShouldBeNil) @@ -174,15 +176,16 @@ func TestCameraWithNoProjector(t *testing.T) { test.That(t, errors.Is(err, transform.ErrNoIntrinsics), test.ShouldBeTrue) // make a camera with a NextPointCloudFunction - videoSrc2 := &cloudSource{Named: camera.Named("foo").AsNamed(), simpleSource: videoSrc} - noProj2, err := camera.NewVideoSourceFromReader(context.Background(), videoSrc2, nil, camera.DepthStream) + cloudSrc2 := &cloudSource{Named: camera.Named("foo").AsNamed(), simpleSource: videoSrc} + videoSrc2, err := camera.NewVideoSourceFromReader(context.Background(), cloudSrc2, nil, camera.DepthStream) + noProj2 := camera.FromVideoSource(resource.NewName(camera.API, "bar"), videoSrc2, logger) test.That(t, err, test.ShouldBeNil) pc, err := noProj2.NextPointCloud(context.Background()) test.That(t, err, test.ShouldBeNil) _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.ImageFromVideoSource(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) + img, err := camera.GoImageFromCamera(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) @@ -192,6 +195,7 @@ func TestCameraWithNoProjector(t *testing.T) { } func TestCameraWithProjector(t *testing.T) { + logger := logging.NewTestLogger(t) videoSrc := &simpleSource{"rimage/board1"} params1 := &transform.PinholeCameraIntrinsics{ // not the real camera parameters -- fake for test Width: 1280, @@ -214,34 +218,35 @@ func TestCameraWithProjector(t *testing.T) { test.That(t, src.Close(context.Background()), test.ShouldBeNil) // camera with a point cloud function - videoSrc2 := &cloudSource{Named: camera.Named("foo").AsNamed(), simpleSource: videoSrc} + cloudSrc2 := &cloudSource{Named: camera.Named("foo").AsNamed(), simpleSource: videoSrc} props, err := src.Properties(context.Background()) test.That(t, err, test.ShouldBeNil) - cam2, err := camera.NewVideoSourceFromReader( + videoSrc2, err := camera.NewVideoSourceFromReader( context.Background(), - videoSrc2, + cloudSrc2, &transform.PinholeCameraModel{PinholeCameraIntrinsics: props.IntrinsicParams}, camera.DepthStream, ) + cam2 := camera.FromVideoSource(resource.NewName(camera.API, "bar"), videoSrc2, logger) test.That(t, err, test.ShouldBeNil) - pc, err = cam2.NextPointCloud(context.Background()) + pc, err = videoSrc2.NextPointCloud(context.Background()) test.That(t, err, test.ShouldBeNil) _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypePNG, nil, cam2) + img, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypePNG, nil, cam2) test.That(t, err, test.ShouldBeNil) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) test.That(t, img.Bounds().Dy(), test.ShouldEqual, 720) // cam2 should implement a default GetImages, that just returns the one image - images, _, err := cam2.Images(context.Background()) + images, _, err := videoSrc2.Images(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, len(images), test.ShouldEqual, 1) test.That(t, images[0].Image, test.ShouldHaveSameTypeAs, &rimage.DepthMap{}) test.That(t, images[0].Image.Bounds().Dx(), test.ShouldEqual, 1280) test.That(t, images[0].Image.Bounds().Dy(), test.ShouldEqual, 720) - test.That(t, cam2.Close(context.Background()), test.ShouldBeNil) + test.That(t, videoSrc2.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/client.go b/components/camera/client.go index 86152b092e3..0feda87fdb8 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -146,7 +146,7 @@ func (c *client) Stream( return } - img, err := ImageFromVideoSource(streamCtx, mimeTypeFromCtx, nil, c) + img, err := GoImageFromCamera(streamCtx, mimeTypeFromCtx, nil, c) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 26b4c930447..031a12c1ca2 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -178,12 +178,12 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - frame, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) + frame, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion - _, err = camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeRawRGBA, map[string]interface{}{"empty": true}, camera1Client) + _, err = camera.GoImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, map[string]interface{}{"empty": true}, camera1Client) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "received empty bytes from Image method") @@ -228,7 +228,7 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frame, err := camera.ImageFromVideoSource(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) + frame, err := camera.GoImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) @@ -469,7 +469,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frame, err := camera.ImageFromVideoSource(ctx, rutils.MimeTypePNG, nil, camera1Client) + frame, err := camera.GoImageFromCamera(ctx, rutils.MimeTypePNG, nil, camera1Client) test.That(t, err, test.ShouldBeNil) // Should always lazily decode test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) @@ -477,7 +477,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) ctx = context.Background() - frame, err = camera.ImageFromVideoSource(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) + frame, err = camera.GoImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) test.That(t, err, test.ShouldBeNil) test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) frameLazy = frame.(*rimage.LazyEncodedImage) diff --git a/components/camera/collectors_test.go b/components/camera/collectors_test.go index e4d7e23983a..2b4a596077d 100644 --- a/components/camera/collectors_test.go +++ b/components/camera/collectors_test.go @@ -185,11 +185,11 @@ func newCamera( ) camera.Camera { v := &inject.Camera{} v.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - resBytes, err := rimage.EncodeImage(ctx, left, mimeType) + viamLogoJpegBytes, err := io.ReadAll(base64.NewDecoder(base64.StdEncoding, bytes.NewReader(viamLogoJpegB64))) if err != nil { return nil, camera.ImageMetadata{}, err } - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return viamLogoJpegBytes, camera.ImageMetadata{MimeType: mimeType}, nil } v.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index c8c39058157..7760e2fcb53 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -94,7 +94,7 @@ func TestRTPPassthrough(t *testing.T) { cam, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) - img, err := camera.ImageFromVideoSource(context.Background(), utils.MimeTypeRawRGBA, nil, cam) + img, err := camera.GoImageFromCamera(context.Background(), utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index cd089d91c31..71835d0db01 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -102,7 +102,7 @@ func TestColorOddResolution(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - strmImg, err := camera.ImageFromVideoSource(ctx, utils.MimeTypeRawRGBA, nil, cam) + strmImg, err := camera.GoImageFromCamera(ctx, utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) expectedBounds := image.Rect(0, 0, img.Bounds().Dx()-1, img.Bounds().Dy()-1) diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 06ae4692c5c..93170353bc8 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -584,7 +584,7 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - frame, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) + frame, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index d580075613f..9f942b2171c 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -93,7 +93,7 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - pic, err := camera.ImageFromVideoSource(context.Background(), rutils.MimeTypeJPEG, nil, c1) + pic, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypeJPEG, nil, c1) test.That(t, err, test.ShouldBeNil) bounds := pic.Bounds() From 9a9612f71e0459e352e3a46c57f5b0c10c8f8c15 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 16:35:59 -0500 Subject: [PATCH 46/51] If err, then bytes and metadata should be falsy --- robot/client/client_test.go | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 93170353bc8..6a54c4b60c4 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -506,9 +506,11 @@ func TestStatusClient(t *testing.T) { camera1, err := camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - _, _, err = camera1.Image(context.Background(), rutils.MimeTypeJPEG, nil) + imgBytes, metadata, err := camera1.Image(context.Background(), rutils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "not found") + test.That(t, imgBytes, test.ShouldBeNil) + test.That(t, metadata, test.ShouldEqual, camera.ImageMetadata{}) gripper1, err := gripper.FromRobot(client, "gripper1") test.That(t, err, test.ShouldBeNil) From ab7e7366b7812eed306f8162c474e562f38c1065 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 14 Nov 2024 16:40:15 -0500 Subject: [PATCH 47/51] Use imgbuf bytes directly for a robot client test rather than encode from img; Fix prev test bug --- components/camera/camera.go | 6 +++--- components/camera/camera_test.go | 4 ++-- components/camera/client.go | 2 +- components/camera/client_test.go | 10 +++++----- components/camera/fake/camera_test.go | 2 +- components/camera/fake/image_file_test.go | 2 +- robot/client/client_test.go | 8 +++----- robot/impl/local_robot_test.go | 2 +- 8 files changed, 17 insertions(+), 19 deletions(-) diff --git a/components/camera/camera.go b/components/camera/camera.go index 1c6732f45a9..e010f2f5a22 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -96,7 +96,7 @@ type Camera interface { // Or try to directly decode into an image.Image: // // myCamera, err := camera.FromRobot(machine, "my_camera") -// img, err = camera.ImageFromVideoSource(context.Background(), utils.MimeTypeJPEG, nil, myCamera) +// img, err = camera.DecodeImageFromCamera(context.Background(), utils.MimeTypeJPEG, nil, myCamera) // // Images example: // @@ -159,8 +159,8 @@ func ReadImage(ctx context.Context, src gostream.VideoSource) (image.Image, func return gostream.ReadImage(ctx, src) } -// GoImageFromCamera retrieves image bytes from a camera resource and serializes it as an image.Image. -func GoImageFromCamera(ctx context.Context, mimeType string, extra map[string]interface{}, cam Camera) (image.Image, error) { +// DecodeImageFromCamera retrieves image bytes from a camera resource and serializes it as an image.Image. +func DecodeImageFromCamera(ctx context.Context, mimeType string, extra map[string]interface{}, cam Camera) (image.Image, error) { resBytes, resMetadata, err := cam.Image(ctx, mimeType, extra) if err != nil { return nil, fmt.Errorf("could not get image bytes from camera: %w", err) diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index 23a6f44ab0d..4cfd9d99baa 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -185,7 +185,7 @@ func TestCameraWithNoProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.GoImageFromCamera(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) + img, err := camera.DecodeImageFromCamera(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) @@ -234,7 +234,7 @@ func TestCameraWithProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypePNG, nil, cam2) + img, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypePNG, nil, cam2) test.That(t, err, test.ShouldBeNil) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/client.go b/components/camera/client.go index 0feda87fdb8..e717e9868d3 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -146,7 +146,7 @@ func (c *client) Stream( return } - img, err := GoImageFromCamera(streamCtx, mimeTypeFromCtx, nil, c) + img, err := DecodeImageFromCamera(streamCtx, mimeTypeFromCtx, nil, c) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 031a12c1ca2..0acceee499d 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -178,12 +178,12 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - frame, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) + frame, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion - _, err = camera.GoImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, map[string]interface{}{"empty": true}, camera1Client) + _, err = camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, map[string]interface{}{"empty": true}, camera1Client) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "received empty bytes from Image method") @@ -228,7 +228,7 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frame, err := camera.GoImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) + frame, err := camera.DecodeImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) @@ -469,7 +469,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frame, err := camera.GoImageFromCamera(ctx, rutils.MimeTypePNG, nil, camera1Client) + frame, err := camera.DecodeImageFromCamera(ctx, rutils.MimeTypePNG, nil, camera1Client) test.That(t, err, test.ShouldBeNil) // Should always lazily decode test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) @@ -477,7 +477,7 @@ func TestClientLazyImage(t *testing.T) { test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) ctx = context.Background() - frame, err = camera.GoImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) + frame, err = camera.DecodeImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) test.That(t, err, test.ShouldBeNil) test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) frameLazy = frame.(*rimage.LazyEncodedImage) diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index 7760e2fcb53..4d14c1ca7ba 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -94,7 +94,7 @@ func TestRTPPassthrough(t *testing.T) { cam, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) - img, err := camera.GoImageFromCamera(context.Background(), utils.MimeTypeRawRGBA, nil, cam) + img, err := camera.DecodeImageFromCamera(context.Background(), utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index 71835d0db01..86fbe1ff325 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -102,7 +102,7 @@ func TestColorOddResolution(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - strmImg, err := camera.GoImageFromCamera(ctx, utils.MimeTypeRawRGBA, nil, cam) + strmImg, err := camera.DecodeImageFromCamera(ctx, utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) expectedBounds := image.Rect(0, 0, img.Bounds().Dx()-1, img.Bounds().Dy()-1) diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 6a54c4b60c4..27b70d954c9 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -332,9 +332,7 @@ func TestStatusClient(t *testing.T) { test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil) injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - resBytes, err := rimage.EncodeImage(ctx, img, mimeType) - test.That(t, err, test.ShouldBeNil) - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return imgBuf.Bytes(), camera.ImageMetadata{MimeType: rutils.MimeTypePNG}, nil } injectInputDev := &inject.InputController{} @@ -510,7 +508,7 @@ func TestStatusClient(t *testing.T) { test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "not found") test.That(t, imgBytes, test.ShouldBeNil) - test.That(t, metadata, test.ShouldEqual, camera.ImageMetadata{}) + test.That(t, metadata, test.ShouldResemble, camera.ImageMetadata{}) gripper1, err := gripper.FromRobot(client, "gripper1") test.That(t, err, test.ShouldBeNil) @@ -586,7 +584,7 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - frame, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) + frame, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 9f942b2171c..3a66436c69d 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -93,7 +93,7 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - pic, err := camera.GoImageFromCamera(context.Background(), rutils.MimeTypeJPEG, nil, c1) + pic, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeJPEG, nil, c1) test.That(t, err, test.ShouldBeNil) bounds := pic.Bounds() From 8244dfde3fcc42f5682cf6893a05d97c480e7ac0 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Fri, 15 Nov 2024 11:38:33 -0500 Subject: [PATCH 48/51] Add back ReadImage/Stream tests where it makes sense --- components/camera/camera_test.go | 35 ++++++++++++++++- components/camera/client_test.go | 48 +++++++++++++++++++++++ components/camera/fake/camera_test.go | 14 +++++++ components/camera/fake/image_file_test.go | 39 ++++++++++++++++++ components/camera/ffmpeg/ffmpeg_test.go | 8 +++- robot/client/client_test.go | 18 +++++++++ robot/impl/local_robot_test.go | 9 +++++ 7 files changed, 169 insertions(+), 2 deletions(-) diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index 4cfd9d99baa..43c5951548f 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -10,6 +10,7 @@ import ( "go.viam.com/utils/artifact" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/gostream" "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" @@ -185,6 +186,18 @@ func TestCameraWithNoProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) + // TODO(hexbabe): remove below test when Stream is refactored + t.Run("ReadImage depth map without projector", func(t *testing.T) { + img, _, err := camera.ReadImage( + gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)), + noProj2) + test.That(t, err, test.ShouldBeNil) + depthImg := img.(*rimage.DepthMap) + test.That(t, err, test.ShouldBeNil) + test.That(t, depthImg.Bounds().Dx(), test.ShouldEqual, 1280) + test.That(t, depthImg.Bounds().Dy(), test.ShouldEqual, 720) + }) + img, err := camera.DecodeImageFromCamera(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) test.That(t, err, test.ShouldBeNil) @@ -234,6 +247,26 @@ func TestCameraWithProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("ReadImage depth map with projector", func(t *testing.T) { + img, _, err := camera.ReadImage( + gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG), + cam2) + test.That(t, err, test.ShouldBeNil) + + depthImg := img.(*rimage.DepthMap) + test.That(t, err, test.ShouldBeNil) + test.That(t, depthImg.Bounds().Dx(), test.ShouldEqual, 1280) + test.That(t, depthImg.Bounds().Dy(), test.ShouldEqual, 720) + // cam2 should implement a default GetImages, that just returns the one image + images, _, err := cam2.Images(context.Background()) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(images), test.ShouldEqual, 1) + test.That(t, images[0].Image, test.ShouldHaveSameTypeAs, &rimage.DepthMap{}) + test.That(t, images[0].Image.Bounds().Dx(), test.ShouldEqual, 1280) + test.That(t, images[0].Image.Bounds().Dy(), test.ShouldEqual, 720) + }) + img, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypePNG, nil, cam2) test.That(t, err, test.ShouldBeNil) @@ -248,5 +281,5 @@ func TestCameraWithProjector(t *testing.T) { test.That(t, images[0].Image.Bounds().Dx(), test.ShouldEqual, 1280) test.That(t, images[0].Image.Bounds().Dy(), test.ShouldEqual, 720) - test.That(t, videoSrc2.Close(context.Background()), test.ShouldBeNil) + test.That(t, cam2.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 0acceee499d..d67ea2bf2ae 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -178,6 +178,17 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("ReadImage from camera client 1", func(t *testing.T) { + ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA) + stream, err := camera1Client.Stream(ctx) + test.That(t, err, test.ShouldBeNil) + frame, _, err := stream.Next(ctx) + test.That(t, err, test.ShouldBeNil) + compVal, _, err := rimage.CompareImages(img, frame) + test.That(t, err, test.ShouldBeNil) + test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion + }) frame, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) @@ -227,6 +238,17 @@ func TestClient(t *testing.T) { client, err := resourceAPI.RPCClient(context.Background(), conn, "", camera.Named(depthCameraName), logger) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("ReadImage from camera depth", func(t *testing.T) { + ctx := gostream.WithMIMETypeHint( + context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)) + frame, _, err := camera.ReadImage(ctx, client) + test.That(t, err, test.ShouldBeNil) + dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) + test.That(t, err, test.ShouldBeNil) + test.That(t, dm, test.ShouldResemble, depthImg) + }) + ctx := context.Background() frame, err := camera.DecodeImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) test.That(t, err, test.ShouldBeNil) @@ -271,6 +293,12 @@ func TestClient(t *testing.T) { } ctx := context.Background() + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("ReadImage test failure", func(t *testing.T) { + _, _, err = camera.ReadImage(ctx, camClient) + test.That(t, err, test.ShouldNotBeNil) + test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) + }) _, _, err = camClient.Image(ctx, "", nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) @@ -468,6 +496,17 @@ func TestClientLazyImage(t *testing.T) { camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("lazily decode from ReadImage without lazy suffix", func(t *testing.T) { + ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG) + frame, _, err := camera.ReadImage(ctx, camera1Client) + test.That(t, err, test.ShouldBeNil) + // Should always lazily decode + test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) + frameLazy := frame.(*rimage.LazyEncodedImage) + test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) + }) + ctx := context.Background() frame, err := camera.DecodeImageFromCamera(ctx, rutils.MimeTypePNG, nil, camera1Client) test.That(t, err, test.ShouldBeNil) @@ -476,6 +515,15 @@ func TestClientLazyImage(t *testing.T) { frameLazy := frame.(*rimage.LazyEncodedImage) test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("lazily decode from ReadImage", func(t *testing.T) { + ctx = gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)) + frame, _, err = camera.ReadImage(ctx, camera1Client) + test.That(t, err, test.ShouldBeNil) + test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) + frameLazy = frame.(*rimage.LazyEncodedImage) + }) + ctx = context.Background() frame, err = camera.DecodeImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index 4d14c1ca7ba..06e766baef4 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -94,6 +94,20 @@ func TestRTPPassthrough(t *testing.T) { cam, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("test Stream and Next", func(t *testing.T) { + camera, err := NewCamera(context.Background(), nil, cfg, logger) + test.That(t, err, test.ShouldBeNil) + + stream, err := camera.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + img, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + // GetImage returns the world jpeg + test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) + test.That(t, camera, test.ShouldNotBeNil) + }) + img, err := camera.DecodeImageFromCamera(context.Background(), utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index 86fbe1ff325..c1415b5265a 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -27,6 +27,10 @@ func TestPCD(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + _, err = cam.Stream(ctx) + test.That(t, err, test.ShouldBeNil) + pc, err := cam.NextPointCloud(ctx) test.That(t, err, test.ShouldBeNil) test.That(t, pc.Size(), test.ShouldEqual, 628) @@ -46,6 +50,16 @@ func TestPCD(t *testing.T) { readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("test Stream and Next", func(t *testing.T) { + stream, err := cam.Stream(ctx) + test.That(t, err, test.ShouldBeNil) + strmImg, _, err := stream.Next(ctx) + test.That(t, err, test.ShouldBeNil) + test.That(t, strmImg, test.ShouldResemble, readInImage) + test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds()) + }) + imgBytes, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldBeNil) expectedBytes, err := rimage.EncodeImage(ctx, readInImage, utils.MimeTypeJPEG) @@ -70,6 +84,16 @@ func TestColor(t *testing.T) { readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("test Stream and Next", func(t *testing.T) { + stream, err := cam.Stream(ctx) + test.That(t, err, test.ShouldBeNil) + strmImg, _, err := stream.Next(ctx) + test.That(t, err, test.ShouldBeNil) + test.That(t, strmImg, test.ShouldResemble, readInImage) + test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds()) + }) + imgBytes, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldBeNil) expectedBytes, err := rimage.EncodeImage(ctx, readInImage, utils.MimeTypeJPEG) @@ -102,6 +126,21 @@ func TestColorOddResolution(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("test Stream and Next", func(t *testing.T) { + stream, err := cam.Stream(ctx) + test.That(t, err, test.ShouldBeNil) + + readInImage, err := rimage.NewImageFromFile(imgFilePath) + test.That(t, err, test.ShouldBeNil) + + strmImg, _, err := stream.Next(ctx) + test.That(t, err, test.ShouldBeNil) + + expectedBounds := image.Rect(0, 0, readInImage.Bounds().Dx()-1, readInImage.Bounds().Dy()-1) + test.That(t, strmImg, test.ShouldResemble, readInImage.SubImage(expectedBounds)) + }) + strmImg, err := camera.DecodeImageFromCamera(ctx, utils.MimeTypeRawRGBA, nil, cam) test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/ffmpeg/ffmpeg_test.go b/components/camera/ffmpeg/ffmpeg_test.go index d03f79e6a0f..f8f9fb5f626 100644 --- a/components/camera/ffmpeg/ffmpeg_test.go +++ b/components/camera/ffmpeg/ffmpeg_test.go @@ -18,10 +18,16 @@ func TestFFMPEGCamera(t *testing.T) { path := artifact.MustPath("components/camera/ffmpeg/testsrc.mpg") cam, err := NewFFMPEGCamera(ctx, &Config{VideoPath: path}, logger) test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + stream, err := cam.Stream(ctx) + test.That(t, err, test.ShouldBeNil) for i := 0; i < 5; i++ { - _, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) + _, _, err := stream.Next(ctx) + test.That(t, err, test.ShouldBeNil) + _, _, err = cam.Image(ctx, utils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldBeNil) } + test.That(t, stream.Close(context.Background()), test.ShouldBeNil) test.That(t, cam.Close(context.Background()), test.ShouldBeNil) } diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 27b70d954c9..d5802efd7e6 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -55,6 +55,7 @@ import ( "go.viam.com/rdk/components/sensor" "go.viam.com/rdk/components/servo" "go.viam.com/rdk/config" + "go.viam.com/rdk/gostream" rgrpc "go.viam.com/rdk/grpc" "go.viam.com/rdk/logging" "go.viam.com/rdk/operation" @@ -504,6 +505,12 @@ func TestStatusClient(t *testing.T) { camera1, err := camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("ReadImage on missing camera", func(t *testing.T) { + _, _, err = camera.ReadImage(context.Background(), camera1) + test.That(t, err, test.ShouldNotBeNil) + test.That(t, err.Error(), test.ShouldContainSubstring, "not found") + }) imgBytes, metadata, err := camera1.Image(context.Background(), rutils.MimeTypeJPEG, nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "not found") @@ -584,6 +591,17 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) + + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("ReadImage on camera with valid response", func(t *testing.T) { + ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA) + frame, _, err := camera.ReadImage(ctx, camera1) + test.That(t, err, test.ShouldBeNil) + compVal, _, err := rimage.CompareImages(img, frame) + test.That(t, err, test.ShouldBeNil) + test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion + }) + frame, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 3a66436c69d..ac273051f31 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -93,6 +93,15 @@ func TestConfig1(t *testing.T) { c1, err := camera.FromRobot(r, "c1") test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) + + // TODO(hexbabe): remove below test when Stream/ReadImage pattern is refactored + t.Run("ReadImage from camera", func(t *testing.T) { + pic, _, err := camera.ReadImage(context.Background(), c1) + test.That(t, err, test.ShouldBeNil) + bounds := pic.Bounds() + test.That(t, bounds.Max.X, test.ShouldBeGreaterThanOrEqualTo, 32) + }) + pic, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeJPEG, nil, c1) test.That(t, err, test.ShouldBeNil) From be2bfee707f9b368818b4ff84c07cc0a0f6efcc0 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 20 Nov 2024 16:52:40 -0500 Subject: [PATCH 49/51] Branch off rsdk-9132 --- data/collector.go | 14 ++++++++++++++ web/cmd/server/main.go | 11 ++++++++++- 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/data/collector.go b/data/collector.go index 7070141147e..bde12750a93 100644 --- a/data/collector.go +++ b/data/collector.go @@ -78,6 +78,8 @@ type collector struct { captureFunc CaptureFunc target CaptureBufferedWriter lastLoggedErrors map[string]int64 + + lastCaptureTime time.Time } // Close closes the channels backing the Collector. It should always be called before disposing of a Collector to avoid @@ -196,6 +198,18 @@ func (c *collector) getAndPushNextReading() { return } + // debug freq calculation + if !c.lastCaptureTime.IsZero() { + elapsed := timeReceived.AsTime().Sub(c.lastCaptureTime).Seconds() + if elapsed > 0 { + frequency := 1.0 / elapsed + c.logger.Infow("capture frequency", "frequency_hz", frequency) + } else { + panic("oh no") + } + } + c.lastCaptureTime = timeReceived.AsTime() + var msg v1.SensorData switch v := reading.(type) { case []byte: diff --git a/web/cmd/server/main.go b/web/cmd/server/main.go index e8d3816d498..f30ea65d6c7 100644 --- a/web/cmd/server/main.go +++ b/web/cmd/server/main.go @@ -3,12 +3,18 @@ package main import ( + "log" + "net/http" + "go.viam.com/utils" // registers all components. _ "go.viam.com/rdk/components/register" "go.viam.com/rdk/logging" + // registers all services. + _ "net/http/pprof" + _ "go.viam.com/rdk/services/register" "go.viam.com/rdk/web/server" ) @@ -16,5 +22,8 @@ import ( var logger = logging.NewDebugLogger("entrypoint") func main() { + go func() { + log.Println(http.ListenAndServe("localhost:6061", nil)) + }() utils.ContextualMain(server.RunServer, logger) -} +} \ No newline at end of file From 3aaf0fe26073d74c8bcde35f2ebfd06a719dcf68 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 20 Nov 2024 17:02:16 -0500 Subject: [PATCH 50/51] Change host name --- web/cmd/server/main.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/web/cmd/server/main.go b/web/cmd/server/main.go index f30ea65d6c7..4a551006df2 100644 --- a/web/cmd/server/main.go +++ b/web/cmd/server/main.go @@ -23,7 +23,7 @@ var logger = logging.NewDebugLogger("entrypoint") func main() { go func() { - log.Println(http.ListenAndServe("localhost:6061", nil)) + log.Println(http.ListenAndServe("0.0.0.0:6061", nil)) }() utils.ContextualMain(server.RunServer, logger) } \ No newline at end of file From e16d187c902ebc9cf902a611b4934760730da010 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Thu, 21 Nov 2024 14:56:00 -0500 Subject: [PATCH 51/51] Add latency calc --- data/collector.go | 25 +++++++++++++++---------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/data/collector.go b/data/collector.go index bde12750a93..79c81197171 100644 --- a/data/collector.go +++ b/data/collector.go @@ -184,6 +184,8 @@ func (c *collector) getAndPushNextReading() { timeRequested := timestamppb.New(c.clock.Now().UTC()) reading, err := c.captureFunc(c.cancelCtx, c.params) timeReceived := timestamppb.New(c.clock.Now().UTC()) + latency := timeReceived.AsTime().Sub(timeRequested.AsTime()) + elapsed := timeReceived.AsTime().Sub(c.lastCaptureTime).Seconds() if c.cancelCtx.Err() != nil { return @@ -198,17 +200,20 @@ func (c *collector) getAndPushNextReading() { return } - // debug freq calculation - if !c.lastCaptureTime.IsZero() { - elapsed := timeReceived.AsTime().Sub(c.lastCaptureTime).Seconds() - if elapsed > 0 { - frequency := 1.0 / elapsed - c.logger.Infow("capture frequency", "frequency_hz", frequency) - } else { - panic("oh no") - } + // debug on success + if !c.lastCaptureTime.IsZero() { + if elapsed > 0 { + frequency := 1.0 / elapsed + c.logger.Infow("capture metrics", + "frequency_hz", frequency, + "latency_ms", latency.Milliseconds(), + "time_received", timeReceived.AsTime(), + ) + } else { + panic("oh no") } - c.lastCaptureTime = timeReceived.AsTime() + } + c.lastCaptureTime = timeReceived.AsTime() var msg v1.SensorData switch v := reading.(type) {