From d6439dd29e1933aaffc6ed2c2cf49095cd9f6315 Mon Sep 17 00:00:00 2001 From: hexbabe Date: Wed, 6 Nov 2024 12:21:47 -0500 Subject: [PATCH] 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.