diff --git a/components/camera/camera.go b/components/camera/camera.go index 482fdd578f3..320f5960066 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -10,20 +10,17 @@ import ( "fmt" "image" "strings" - "time" "github.com/pkg/errors" pb "go.viam.com/api/component/camera/v1" "go.viam.com/rdk/data" "go.viam.com/rdk/gostream" - "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/robot" - "go.viam.com/rdk/utils" ) // ErrMIMETypeBytesMismatch indicates that the NamedImage's mimeType does not match the image bytes header. @@ -218,10 +215,6 @@ type Camera interface { resource.Resource resource.Shaped - // Image returns a byte slice representing an image that tries to adhere to the MIME type hint. - // Image also may return metadata about the frame. - Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) - // Images is used for getting simultaneous images from different imagers, // along with associated metadata (just timestamp for now). It's not for getting a time series of images from the same imager. // The extra parameter can be used to pass additional options to the camera resource. The filterSourceNames parameter can be used to filter @@ -237,122 +230,6 @@ type Camera interface { Properties(ctx context.Context) (Properties, error) } -// DecodeImageFromCamera retrieves image bytes from a camera resource and serializes it as an image.Image. -func DecodeImageFromCamera(ctx context.Context, mimeType string, extra map[string]interface{}, cam Camera) (image.Image, error) { - resBytes, resMetadata, err := cam.Image(ctx, mimeType, extra) - if err != nil { - return nil, fmt.Errorf("could not get image bytes from camera: %w", err) - } - if len(resBytes) == 0 { - return nil, errors.New("received empty bytes from camera") - } - img, err := rimage.DecodeImage(ctx, resBytes, utils.WithLazyMIMEType(resMetadata.MimeType)) - if err != nil { - return nil, fmt.Errorf("could not decode into image.Image: %w", err) - } - return img, nil -} - -// GetImageFromGetImages will be deprecated after RSDK-11726. -// It is a utility function to quickly implement GetImage from an already-implemented GetImages method. -// It returns a byte slice and ImageMetadata, which is the same response signature as the Image method. -// -// If sourceName is nil, it returns the first image in the response slice. -// If sourceName is not nil, it returns the image with the matching source name. -// If no image is found with the matching source name, it returns an error. -// -// It uses the mimeType arg to specify how to encode the bytes returned from GetImages. -// The extra parameter is passed through to the underlying Images method. -func GetImageFromGetImages( - ctx context.Context, - sourceName *string, - cam Camera, - extra map[string]interface{}, - filterSourceNames []string, -) ([]byte, ImageMetadata, error) { - sourceNames := []string{} - if sourceName != nil { - sourceNames = append(sourceNames, *sourceName) - } - namedImages, _, err := cam.Images(ctx, sourceNames, extra) - if err != nil { - return nil, ImageMetadata{}, fmt.Errorf("could not get images from camera: %w", err) - } - if len(namedImages) == 0 { - return nil, ImageMetadata{}, errors.New("no images returned from camera") - } - - var img image.Image - var mimeType string - if sourceName == nil { - img, err = namedImages[0].Image(ctx) - if err != nil { - return nil, ImageMetadata{}, fmt.Errorf("could not get image from named image: %w", err) - } - mimeType = namedImages[0].MimeType() - } else { - for _, i := range namedImages { - if i.SourceName == *sourceName { - img, err = i.Image(ctx) - if err != nil { - return nil, ImageMetadata{}, fmt.Errorf("could not get image from named image: %w", err) - } - mimeType = i.MimeType() - break - } - } - if img == nil { - return nil, ImageMetadata{}, errors.New("no image found with source name: " + *sourceName) - } - } - - if img == nil { - return nil, ImageMetadata{}, errors.New("image is nil") - } - - imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) - if err != nil { - return nil, ImageMetadata{}, fmt.Errorf("could not encode image with encoding %s: %w", mimeType, err) - } - return imgBytes, ImageMetadata{MimeType: mimeType}, nil -} - -// GetImagesFromGetImage will be deprecated after RSDK-11726. -// It is a utility function to quickly implement GetImages from an already-implemented GetImage method. -// It takes a mimeType, extra parameters, and a camera as args, and returns a slice of NamedImage and ResponseMetadata, -// which is the same response signature as the Images method. We use the mimeType arg to specify -// how to decode the image bytes returned from GetImage. The extra parameter is passed through to the underlying GetImage method. -// Source name is empty string always. -// It returns a slice of NamedImage of length 1 and ResponseMetadata, with empty string as the source name. -func GetImagesFromGetImage( - ctx context.Context, - mimeType string, - cam Camera, - logger logging.Logger, - extra map[string]interface{}, -) ([]NamedImage, resource.ResponseMetadata, error) { - resBytes, resMetadata, err := cam.Image(ctx, mimeType, extra) - if err != nil { - return nil, resource.ResponseMetadata{}, fmt.Errorf("could not get image bytes from camera: %w", err) - } - if len(resBytes) == 0 { - return nil, resource.ResponseMetadata{}, errors.New("received empty bytes from camera") - } - - resMimetype, _ := utils.CheckLazyMIMEType(resMetadata.MimeType) - reqMimetype, _ := utils.CheckLazyMIMEType(mimeType) - if resMimetype != reqMimetype { - logger.Warnf("requested mime type %s, but received %s", mimeType, resMimetype) - } - - namedImg, err := NamedImageFromBytes(resBytes, "", resMetadata.MimeType) - if err != nil { - return nil, resource.ResponseMetadata{}, fmt.Errorf("could not create named image: %w", err) - } - - return []NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil -} - // VideoSource is a camera that has `Stream` embedded to directly integrate with gostream. // Note that generally, when writing camera components from scratch, embedding `Stream` is an anti-pattern. type VideoSource interface { diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index 5c3d909e9b2..58d19e0e2a1 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -13,7 +13,6 @@ import ( "go.viam.com/utils/artifact" "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -191,7 +190,10 @@ func TestCameraWithNoProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.DecodeImageFromCamera(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, noProj2) + namedImages, _, err := noProj2.Images(context.Background(), nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + img, err := namedImages[0].Image(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) @@ -239,10 +241,12 @@ func TestCameraWithProjector(t *testing.T) { _, got := pc.At(0, 0, 0) test.That(t, got, test.ShouldBeTrue) - img, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypePNG, nil, cam2) + namedImages, _, err := cam2.Images(context.Background(), nil, nil) test.That(t, err, test.ShouldBeNil) - + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + img, err := namedImages[0].Image(context.Background()) test.That(t, err, test.ShouldBeNil) + test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) test.That(t, img.Bounds().Dy(), test.ShouldEqual, 720) // cam2 should implement a default GetImages, that just returns the one image @@ -258,215 +262,6 @@ func TestCameraWithProjector(t *testing.T) { test.That(t, cam2.Close(context.Background()), test.ShouldBeNil) } -// verifyDecodedImage verifies that decoded image bytes match the original image. -func verifyDecodedImage(t *testing.T, imgBytes []byte, mimeType string, originalImg image.Image) { - t.Helper() - test.That(t, len(imgBytes), test.ShouldBeGreaterThan, 0) - - // For JPEG, compare the raw bytes instead of the decoded image since the decoded image is - // not guaranteed to be the same as the original image due to lossy compression. - if mimeType == rutils.MimeTypeJPEG { - expectedBytes, err := rimage.EncodeImage(context.Background(), originalImg, mimeType) - test.That(t, err, test.ShouldBeNil) - test.That(t, imgBytes, test.ShouldResemble, expectedBytes) - return - } - - // For other formats, compare the decoded images - decodedImg, err := rimage.DecodeImage(context.Background(), imgBytes, mimeType) - test.That(t, err, test.ShouldBeNil) - test.That(t, rimage.ImagesExactlyEqual(decodedImg, originalImg), test.ShouldBeTrue) -} - -func TestGetImageFromGetImages(t *testing.T) { - testImg1 := image.NewRGBA(image.Rect(0, 0, 100, 100)) - testImg2 := image.NewRGBA(image.Rect(0, 0, 200, 200)) - - rgbaCam := inject.NewCamera("rgba_cam") - rgbaCam.ImagesFunc = func( - ctx context.Context, - filterSourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - namedImg1, err := camera.NamedImageFromImage(testImg1, source1Name, rutils.MimeTypeRawRGBA) - if err != nil { - return nil, resource.ResponseMetadata{}, err - } - namedImg2, err := camera.NamedImageFromImage(testImg2, source2Name, rutils.MimeTypeRawRGBA) - if err != nil { - return nil, resource.ResponseMetadata{}, err - } - return []camera.NamedImage{ - namedImg1, - namedImg2, - }, resource.ResponseMetadata{CapturedAt: time.Now()}, nil - } - - dm := rimage.NewEmptyDepthMap(100, 100) - depthCam := inject.NewCamera("depth_cam") - depthCam.ImagesFunc = func( - ctx context.Context, - filterSourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - namedImg, err := camera.NamedImageFromImage(dm, source1Name, rutils.MimeTypeRawDepth) - if err != nil { - return nil, resource.ResponseMetadata{}, err - } - return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil - } - - t.Run("request empty mime type", func(t *testing.T) { - img, metadata, err := camera.GetImageFromGetImages(context.Background(), nil, rgbaCam, nil, nil) - // empty mime type defaults to JPEG - test.That(t, err, test.ShouldBeNil) - test.That(t, img, test.ShouldNotBeNil) - test.That(t, metadata.MimeType, test.ShouldEqual, rutils.MimeTypeRawRGBA) - verifyDecodedImage(t, img, rutils.MimeTypeRawRGBA, testImg1) - }) - - t.Run("error case", func(t *testing.T) { - errorCam := inject.NewCamera("error_cam") - errorCam.ImagesFunc = func( - ctx context.Context, - filterSourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return nil, resource.ResponseMetadata{}, errors.New("test error") - } - _, _, err := camera.GetImageFromGetImages(context.Background(), nil, errorCam, nil, nil) - test.That(t, err, test.ShouldBeError, errors.New("could not get images from camera: test error")) - }) - - t.Run("empty images case", func(t *testing.T) { - emptyCam := inject.NewCamera("empty_cam") - emptyCam.ImagesFunc = func( - ctx context.Context, - filterSourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil - } - _, _, err := camera.GetImageFromGetImages(context.Background(), nil, emptyCam, nil, nil) - test.That(t, err, test.ShouldBeError, errors.New("no images returned from camera")) - }) - - t.Run("nil image case", func(t *testing.T) { - nilImageCam := inject.NewCamera("nil_image_cam") - nilImageCam.ImagesFunc = func( - ctx context.Context, - filterSourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - namedImg, err := camera.NamedImageFromImage(nil, source1Name, rutils.MimeTypeRawRGBA) - if err != nil { - return nil, resource.ResponseMetadata{}, err - } - return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil - } - _, _, err := camera.GetImageFromGetImages(context.Background(), nil, nilImageCam, nil, nil) - test.That(t, err, test.ShouldBeError, - errors.New("could not get images from camera: must provide image to construct a named image from image"), - ) - }) - - t.Run("multiple images, specify source name", func(t *testing.T) { - sourceName := source2Name - img, metadata, err := camera.GetImageFromGetImages(context.Background(), &sourceName, rgbaCam, nil, nil) - test.That(t, err, test.ShouldBeNil) - test.That(t, metadata.MimeType, test.ShouldEqual, rutils.MimeTypeRawRGBA) - verifyDecodedImage(t, img, rutils.MimeTypeRawRGBA, testImg2) - }) -} - -func TestGetImagesFromGetImage(t *testing.T) { - logger := logging.NewTestLogger(t) - testImg := image.NewRGBA(image.Rect(0, 0, 100, 100)) - - rgbaCam := inject.NewCamera("rgba_cam") - rgbaCam.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - imgBytes, err := rimage.EncodeImage(ctx, testImg, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return imgBytes, camera.ImageMetadata{MimeType: mimeType}, nil - } - - t.Run("PNG mime type", func(t *testing.T) { - startTime := time.Now() - images, metadata, err := camera.GetImagesFromGetImage(context.Background(), rutils.MimeTypePNG, rgbaCam, logger, nil) - endTime := time.Now() - test.That(t, err, test.ShouldBeNil) - test.That(t, len(images), test.ShouldEqual, 1) - test.That(t, images[0].SourceName, test.ShouldEqual, "") - img, err := images[0].Image(context.Background()) - test.That(t, err, test.ShouldBeNil) - test.That(t, rimage.ImagesExactlyEqual(img, testImg), test.ShouldBeTrue) - test.That(t, metadata.CapturedAt.IsZero(), test.ShouldBeFalse) - test.That(t, metadata.CapturedAt.After(startTime), test.ShouldBeTrue) - test.That(t, metadata.CapturedAt.Before(endTime), test.ShouldBeTrue) - }) - - t.Run("JPEG mime type", func(t *testing.T) { - startTime := time.Now() - images, metadata, err := camera.GetImagesFromGetImage(context.Background(), rutils.MimeTypeJPEG, rgbaCam, logger, nil) - endTime := time.Now() - test.That(t, err, test.ShouldBeNil) - test.That(t, len(images), test.ShouldEqual, 1) - test.That(t, images[0].SourceName, test.ShouldEqual, "") - img, err := images[0].Image(context.Background()) - test.That(t, err, test.ShouldBeNil) - imgBytes, err := rimage.EncodeImage(context.Background(), img, rutils.MimeTypeJPEG) - test.That(t, err, test.ShouldBeNil) - verifyDecodedImage(t, imgBytes, rutils.MimeTypeJPEG, testImg) - test.That(t, metadata.CapturedAt.IsZero(), test.ShouldBeFalse) - test.That(t, metadata.CapturedAt.After(startTime), test.ShouldBeTrue) - test.That(t, metadata.CapturedAt.Before(endTime), test.ShouldBeTrue) - }) - - t.Run("request mime type depth, but actual image is RGBA", func(t *testing.T) { - rgbaImg := image.NewRGBA(image.Rect(0, 0, 100, 100)) - rgbaCam := inject.NewCamera("rgba_cam") - rgbaCam.ImageFunc = func(ctx context.Context, reqMimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - imgBytes, err := rimage.EncodeImage(ctx, rgbaImg, rutils.MimeTypeRawRGBA) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return imgBytes, camera.ImageMetadata{MimeType: rutils.MimeTypeRawRGBA}, nil - } - startTime := time.Now() - images, metadata, err := camera.GetImagesFromGetImage(context.Background(), rutils.MimeTypeRawDepth, rgbaCam, logger, nil) - endTime := time.Now() - test.That(t, err, test.ShouldBeNil) - test.That(t, len(images), test.ShouldEqual, 1) - test.That(t, images[0].SourceName, test.ShouldEqual, "") - test.That(t, metadata.CapturedAt.IsZero(), test.ShouldBeFalse) - test.That(t, metadata.CapturedAt.After(startTime), test.ShouldBeTrue) - test.That(t, metadata.CapturedAt.Before(endTime), test.ShouldBeTrue) - img, err := images[0].Image(context.Background()) - test.That(t, err, test.ShouldBeNil) - test.That(t, rimage.ImagesExactlyEqual(img, rgbaImg), test.ShouldBeTrue) - }) - - t.Run("error case", func(t *testing.T) { - errorCam := inject.NewCamera("error_cam") - errorCam.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return nil, camera.ImageMetadata{}, errors.New("test error") - } - _, _, err := camera.GetImagesFromGetImage(context.Background(), rutils.MimeTypePNG, errorCam, logger, nil) - test.That(t, err, test.ShouldBeError, errors.New("could not get image bytes from camera: test error")) - }) - - t.Run("empty bytes case", func(t *testing.T) { - emptyCam := inject.NewCamera("empty_cam") - emptyCam.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return []byte{}, camera.ImageMetadata{MimeType: mimeType}, nil - } - _, _, err := camera.GetImagesFromGetImage(context.Background(), rutils.MimeTypePNG, emptyCam, logger, nil) - test.That(t, err, test.ShouldBeError, errors.New("received empty bytes from camera")) - }) -} - // TestImages asserts the core expected behavior of the Images API. func TestImages(t *testing.T) { ctx := context.Background() diff --git a/components/camera/client.go b/components/camera/client.go index 66e355c0d3a..afb3653ae4d 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -148,7 +148,13 @@ func (c *client) Stream( return } - img, err := DecodeImageFromCamera(streamCtx, mimeTypeFromCtx, nil, c) + namedImages, _, err := c.Images(streamCtx, nil, nil) + var img image.Image + if err == nil && len(namedImages) > 0 { + img, err = namedImages[0].Image(streamCtx) + } else if err == nil { + err = errors.New("no images returned from camera") + } if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) @@ -175,39 +181,6 @@ func (c *client) Stream( return stream, nil } -func (c *client) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) { - ctx, span := trace.StartSpan(ctx, "camera::client::Image") - defer span.End() - expectedType, _ := utils.CheckLazyMIMEType(mimeType) - - convertedExtra, err := goprotoutils.StructToStructPb(extra) - if err != nil { - return nil, ImageMetadata{}, err - } - resp, err := c.client.GetImage(ctx, &pb.GetImageRequest{ - Name: c.name, - MimeType: expectedType, - Extra: convertedExtra, - }) - if err != nil { - return nil, ImageMetadata{}, err - } - if len(resp.Image) == 0 { - return nil, ImageMetadata{}, errors.New("received empty bytes from client GetImage") - } - - if expectedType != "" && resp.MimeType != expectedType { - c.logger.CDebugw(ctx, "got different MIME type than what was asked for", "sent", expectedType, "received", resp.MimeType) - if resp.MimeType == "" { - // if the user expected a mime_type and the successful response didn't have a mime type, assume the - // response's mime_type was what the user requested - resp.MimeType = mimeType - } - } - - return resp.Image, ImageMetadata{MimeType: resp.MimeType}, nil -} - func (c *client) Images( ctx context.Context, filterSourceNames []string, @@ -232,11 +205,6 @@ func (c *client) Images( images := make([]NamedImage, 0, len(resp.Images)) // keep everything lazy encoded by default, if type is unknown, attempt to decode it for _, img := range resp.Images { - if img.MimeType == "" { - // TODO(RSDK-11733): This is a temporary fix to allow the client to pass both the format and mime type - // format. We will remove this once we remove the format field from the proto. - img.MimeType = utils.FormatToMimeType[img.Format] - } namedImg, err := NamedImageFromBytes(img.Image, img.SourceName, img.MimeType) if err != nil { return nil, resource.ResponseMetadata{}, err diff --git a/components/camera/client_test.go b/components/camera/client_test.go index 00d3818b560..260d16631b7 100644 --- a/components/camera/client_test.go +++ b/components/camera/client_test.go @@ -6,7 +6,6 @@ import ( "fmt" "image" "image/color" - "image/jpeg" "image/png" "net" "testing" @@ -58,8 +57,6 @@ func TestClient(t *testing.T) { var imgBuf bytes.Buffer test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil) - imgPng, err := png.Decode(bytes.NewReader(imgBuf.Bytes())) - test.That(t, err, test.ShouldBeNil) pcA := pointcloud.NewBasicEmpty() err = pcA.Set(pointcloud.NewVector(5, 5, 5), nil) @@ -115,14 +112,6 @@ func TestClient(t *testing.T) { ts := time.UnixMilli(12345) return images, resource.ResponseMetadata{CapturedAt: ts}, nil } - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - if val, ok := extra["empty"].(bool); ok && val { - return []byte{}, camera.ImageMetadata{}, nil - } - resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) - test.That(t, err, test.ShouldBeNil) - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil - } injectCamera.GeometriesFunc = func(context.Context, map[string]interface{}) ([]spatialmath.Geometry, error) { return expectedGeometries, nil } @@ -146,14 +135,16 @@ func TestClient(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.ImageFunc = func( + injectCameraDepth.ImagesFunc = func( ctx context.Context, - mimeType string, + filterSourceNames []string, extra map[string]interface{}, - ) ([]byte, camera.ImageMetadata, error) { - resBytes, err := rimage.EncodeImage(ctx, depthImg, mimeType) - test.That(t, err, test.ShouldBeNil) - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + namedImg, err := camera.NamedImageFromImage(depthImg, "", rutils.MimeTypeRawDepth) + if err != nil { + return nil, resource.ResponseMetadata{}, err + } + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil } // bad camera injectCamera2 := &inject.Camera{} @@ -166,8 +157,12 @@ func TestClient(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return nil, camera.ImageMetadata{}, errGetImageFailed + injectCamera2.ImagesFunc = func( + ctx context.Context, + filterSourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return nil, resource.ResponseMetadata{}, errGetImageFailed } resources := map[resource.Name]camera.Camera{ @@ -200,14 +195,14 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) test.That(t, err, test.ShouldBeNil) - frame, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1Client) + namedImages, _, err := camera1Client.Images(context.Background(), nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + frame, err := namedImages[0].Image(context.Background()) test.That(t, err, test.ShouldBeNil) - compVal, _, err := rimage.CompareImages(img, frame) + compVal, _, err := rimage.CompareImages(expectedColor, frame) test.That(t, err, test.ShouldBeNil) test.That(t, compVal, test.ShouldEqual, 0) // exact copy, no color conversion - _, err = camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, map[string]interface{}{"empty": true}, camera1Client) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, "received empty bytes from Image method") pcB, err := camera1Client.NextPointCloud(context.Background()) test.That(t, err, test.ShouldBeNil) @@ -261,7 +256,10 @@ func TestClient(t *testing.T) { test.That(t, err, test.ShouldBeNil) ctx := context.Background() - frame, err := camera.DecodeImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, client) + namedImages, _, err := client.Images(ctx, nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + frame, err := namedImages[0].Image(ctx) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) @@ -277,7 +275,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.Image(context.Background(), "", nil) + _, _, err = client2.Images(context.Background(), nil, nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) @@ -291,51 +289,6 @@ func TestClient(t *testing.T) { test.That(t, conn.Close(), test.ShouldBeNil) }) - t.Run("camera client extra", func(t *testing.T) { - conn, err := viamgrpc.Dial(context.Background(), listener1.Addr().String(), logger) - test.That(t, err, test.ShouldBeNil) - - camClient, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) - test.That(t, err, test.ShouldBeNil) - - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - test.That(t, extra, test.ShouldBeEmpty) - return nil, camera.ImageMetadata{}, errGetImageFailed - } - - ctx := context.Background() - _, _, err = camClient.Image(ctx, "", nil) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - test.That(t, len(extra), test.ShouldEqual, 1) - test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - - return nil, camera.ImageMetadata{}, errGetImageFailed - } - - _, _, err = camClient.Image(context.Background(), "", map[string]interface{}{data.FromDMString: true}) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - test.That(t, len(extra), test.ShouldEqual, 2) - test.That(t, extra["hello"], test.ShouldEqual, "world") - test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, camera.ImageMetadata{}, errGetImageFailed - } - - // merge values from data and camera - ext := data.FromDMExtraMap - ext["hello"] = "world" - ctx = context.Background() - _, _, err = camClient.Image(ctx, "", ext) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - - test.That(t, conn.Close(), test.ShouldBeNil) - }) t.Run("camera client images extra", func(t *testing.T) { conn, err := viamgrpc.Dial(context.Background(), listener1.Addr().String(), logger) @@ -631,97 +584,6 @@ func TestClientProperties(t *testing.T) { } } -func TestClientLazyImage(t *testing.T) { - logger := logging.NewTestLogger(t) - listener1, err := net.Listen("tcp", "localhost:0") - test.That(t, err, test.ShouldBeNil) - rpcServer, err := rpc.NewServer(logger, rpc.WithUnauthenticated()) - test.That(t, err, test.ShouldBeNil) - - injectCamera := &inject.Camera{} - img := image.NewNRGBA64(image.Rect(0, 0, 4, 8)) - - var imgBuf bytes.Buffer - test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil) - imgPng, err := png.Decode(bytes.NewReader(imgBuf.Bytes())) - test.That(t, err, test.ShouldBeNil) - var jpegBuf bytes.Buffer - test.That(t, jpeg.Encode(&jpegBuf, img, &jpeg.Options{Quality: 100}), test.ShouldBeNil) - imgJpeg, err := jpeg.Decode(bytes.NewBuffer(jpegBuf.Bytes())) - test.That(t, err, test.ShouldBeNil) - - injectCamera.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { - return camera.Properties{}, nil - } - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - if mimeType == "" { - mimeType = rutils.MimeTypeRawRGBA - } - mimeType, _ = rutils.CheckLazyMIMEType(mimeType) - switch mimeType { - case rutils.MimeTypePNG: - resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) - test.That(t, err, test.ShouldBeNil) - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil - default: - return nil, camera.ImageMetadata{}, errInvalidMimeType - } - } - - resources := map[resource.Name]camera.Camera{ - camera.Named(testCameraName): injectCamera, - } - cameraSvc, err := resource.NewAPIResourceCollection(camera.API, resources) - test.That(t, err, test.ShouldBeNil) - resourceAPI, ok, err := resource.LookupAPIRegistration[camera.Camera](camera.API) - test.That(t, err, test.ShouldBeNil) - test.That(t, ok, test.ShouldBeTrue) - test.That(t, resourceAPI.RegisterRPCService(context.Background(), rpcServer, cameraSvc), test.ShouldBeNil) - - go rpcServer.Serve(listener1) - defer rpcServer.Stop() - - conn, err := viamgrpc.Dial(context.Background(), listener1.Addr().String(), logger) - test.That(t, err, test.ShouldBeNil) - camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger) - test.That(t, err, test.ShouldBeNil) - - ctx := context.Background() - frame, err := camera.DecodeImageFromCamera(ctx, rutils.MimeTypePNG, nil, camera1Client) - test.That(t, err, test.ShouldBeNil) - // Should always lazily decode - test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) - frameLazy := frame.(*rimage.LazyEncodedImage) - test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) - - frame, err = camera.DecodeImageFromCamera(ctx, rutils.WithLazyMIMEType(rutils.MimeTypePNG), nil, camera1Client) - test.That(t, err, test.ShouldBeNil) - test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) - frameLazy = frame.(*rimage.LazyEncodedImage) - test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes()) - - test.That(t, frameLazy.MIMEType(), test.ShouldEqual, rutils.MimeTypePNG) - test.That(t, rimage.ImagesExactlyEqual(frame, img), test.ShouldBeTrue) - - // when DecodeImageFromCamera is called without a mime type, defaults to JPEG - var called bool - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - called = true - test.That(t, mimeType, test.ShouldResemble, rutils.WithLazyMIMEType(rutils.MimeTypeJPEG)) - resBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) - test.That(t, err, test.ShouldBeNil) - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil - } - frame, err = camera.DecodeImageFromCamera(ctx, "", nil, camera1Client) - test.That(t, err, test.ShouldBeNil) - test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{}) - frameLazy = frame.(*rimage.LazyEncodedImage) - test.That(t, frameLazy.MIMEType(), test.ShouldEqual, rutils.MimeTypeJPEG) - test.That(t, rimage.ImagesExactlyEqual(frame, imgJpeg), test.ShouldBeTrue) - test.That(t, called, test.ShouldBeTrue) - test.That(t, conn.Close(), test.ShouldBeNil) -} - func TestClientWithInterceptor(t *testing.T) { // Set up gRPC server logger := logging.NewTestLogger(t) diff --git a/components/camera/collectors.go b/components/camera/collectors.go index f7704be9ee9..2fb2949d44b 100644 --- a/components/camera/collectors.go +++ b/components/camera/collectors.go @@ -113,7 +113,7 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d _, span := trace.StartSpan(ctx, "camera::data::collector::CaptureFunc::ReadImage") defer span.End() - img, metadata, err := camera.Image(ctx, mimeStr, data.FromDMExtraMap) + resImgs, resMetadata, err := camera.Images(ctx, nil, data.FromDMExtraMap) 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. @@ -124,14 +124,41 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d return res, data.NewFailedToReadError(params.ComponentName, readImage.String(), err) } - mimeType := data.CameraFormatToMimeType(utils.MimeTypeToFormat[metadata.MimeType]) + if len(resImgs) == 0 { + err = errors.New("no images returned from camera") + return res, data.NewFailedToReadError(params.ComponentName, readImage.String(), err) + } + + // Select the corresponding image based on requested mime type if provided + var img NamedImage + var foundMatchingMimeType bool + if mimeStr != "" { + for _, candidateImg := range resImgs { + if candidateImg.MimeType() == mimeStr { + img = candidateImg + foundMatchingMimeType = true + break + } + } + } + + if !foundMatchingMimeType { + img = resImgs[0] + } + + imgBytes, err := img.Bytes(ctx) + if err != nil { + return res, data.NewFailedToReadError(params.ComponentName, readImage.String(), err) + } + + mimeType := data.MimeTypeStringToMimeType(img.MimeType()) ts := data.Timestamps{ TimeRequested: timeRequested, - TimeReceived: time.Now(), + TimeReceived: resMetadata.CapturedAt, } return data.NewBinaryCaptureResult(ts, []data.Binary{{ MimeType: mimeType, - Payload: img, + Payload: imgBytes, }}), nil }) return data.NewCollector(cFunc, params) diff --git a/components/camera/collectors_test.go b/components/camera/collectors_test.go index adad8175fcd..8e99f31ecf4 100644 --- a/components/camera/collectors_test.go +++ b/components/camera/collectors_test.go @@ -185,12 +185,20 @@ func newCamera( pcd pointcloud.PointCloud, ) camera.Camera { v := &inject.Camera{} - v.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + v.ImagesFunc = func( + ctx context.Context, + filterSourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { viamLogoJpegBytes, err := io.ReadAll(base64.NewDecoder(base64.StdEncoding, bytes.NewReader(viamLogoJpegB64))) if err != nil { - return nil, camera.ImageMetadata{}, err + return nil, resource.ResponseMetadata{}, err + } + namedImg, err := camera.NamedImageFromBytes(viamLogoJpegBytes, "", utils.MimeTypeJPEG) + if err != nil { + return nil, resource.ResponseMetadata{}, err } - return viamLogoJpegBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil } v.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index 9c8f44088a4..4a0666940a9 100644 --- a/components/camera/fake/camera_test.go +++ b/components/camera/fake/camera_test.go @@ -15,7 +15,6 @@ import ( "go.viam.com/rdk/components/camera/rtppassthrough" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" - "go.viam.com/rdk/utils" ) func TestFakeCameraParams(t *testing.T) { @@ -94,7 +93,10 @@ func TestRTPPassthrough(t *testing.T) { cam, err := NewCamera(context.Background(), nil, cfg, logger) test.That(t, err, test.ShouldBeNil) - img, err := camera.DecodeImageFromCamera(context.Background(), utils.MimeTypeRawRGBA, nil, cam) + namedImages, _, err := cam.Images(context.Background(), nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + img, err := namedImages[0].Image(context.Background()) test.That(t, err, test.ShouldBeNil) // GetImage returns the world jpeg test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}}) diff --git a/components/camera/fake/image_file_test.go b/components/camera/fake/image_file_test.go index 224faca6e6f..4e6ec7493c7 100644 --- a/components/camera/fake/image_file_test.go +++ b/components/camera/fake/image_file_test.go @@ -42,7 +42,9 @@ func TestPCD(t *testing.T) { readInImage, err := rimage.ReadImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) - imgBytes, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) + namedImages, _, err := cam.Images(ctx, nil, nil) + test.That(t, err, test.ShouldBeNil) + imgBytes, err := namedImages[0].Bytes(ctx) test.That(t, err, test.ShouldBeNil) expectedBytes, err := rimage.EncodeImage(ctx, readInImage, utils.MimeTypeJPEG) test.That(t, err, test.ShouldBeNil) @@ -66,7 +68,9 @@ func TestColor(t *testing.T) { readInImage, err := rimage.ReadImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg")) test.That(t, err, test.ShouldBeNil) - imgBytes, _, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) + namedImages, _, err := cam.Images(ctx, nil, nil) + test.That(t, err, test.ShouldBeNil) + imgBytes, err := namedImages[0].Bytes(ctx) test.That(t, err, test.ShouldBeNil) expectedBytes, err := rimage.EncodeImage(ctx, readInImage, utils.MimeTypeJPEG) test.That(t, err, test.ShouldBeNil) @@ -87,7 +91,13 @@ func TestPreloadedImages(t *testing.T) { cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger) test.That(t, err, test.ShouldBeNil) - img, err := camera.DecodeImageFromCamera(ctx, utils.MimeTypeRawRGBA, nil, cam) + namedImages, metadata, err := cam.Images(ctx, nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages), test.ShouldEqual, 1) + test.That(t, namedImages[0].SourceName, test.ShouldEqual, "preloaded") + test.That(t, metadata.CapturedAt.IsZero(), test.ShouldBeFalse) + + img, err := namedImages[0].Image(ctx) test.That(t, err, test.ShouldBeNil) test.That(t, img, test.ShouldNotBeNil) @@ -95,15 +105,9 @@ func TestPreloadedImages(t *testing.T) { test.That(t, bounds.Dx() > 0, test.ShouldBeTrue) test.That(t, bounds.Dy() > 0, test.ShouldBeTrue) - namedImages, metadata, err := cam.Images(ctx, nil, nil) - test.That(t, err, test.ShouldBeNil) - test.That(t, len(namedImages), test.ShouldEqual, 1) - test.That(t, namedImages[0].SourceName, test.ShouldEqual, "preloaded") - test.That(t, metadata.CapturedAt.IsZero(), test.ShouldBeFalse) - - jpegBytes, mime, err := cam.Image(ctx, utils.MimeTypeJPEG, nil) + jpegBytes, err := namedImages[0].Bytes(ctx) test.That(t, err, test.ShouldBeNil) - test.That(t, mime.MimeType, test.ShouldEqual, utils.MimeTypeJPEG) + test.That(t, namedImages[0].MimeType(), test.ShouldEqual, utils.MimeTypeJPEG) test.That(t, len(jpegBytes) > 0, test.ShouldBeTrue) err = cam.Close(ctx) @@ -150,7 +154,9 @@ func TestPreloadedImages(t *testing.T) { test.That(t, err, test.ShouldBeError) test.That(t, err.Error(), test.ShouldEqual, "invalid source name: not a source") - cameraImg, err := camera.DecodeImageFromCamera(ctx, utils.MimeTypeRawRGBA, nil, cam) + namedImages, _, err = cam.Images(ctx, nil, nil) + test.That(t, err, test.ShouldBeNil) + cameraImg, err := namedImages[0].Image(ctx) test.That(t, err, test.ShouldBeNil) preloadedImg, err := getPreloadedImage("pizza") test.That(t, err, test.ShouldBeNil) diff --git a/components/camera/ffmpeg/ffmpeg_test.go b/components/camera/ffmpeg/ffmpeg_test.go index fee3f48782d..32586afcefa 100644 --- a/components/camera/ffmpeg/ffmpeg_test.go +++ b/components/camera/ffmpeg/ffmpeg_test.go @@ -8,9 +8,7 @@ import ( "go.viam.com/test" "go.viam.com/utils/artifact" - "go.viam.com/rdk/components/camera" "go.viam.com/rdk/logging" - "go.viam.com/rdk/utils" ) func TestFFMPEGCamera(t *testing.T) { @@ -21,7 +19,10 @@ func TestFFMPEGCamera(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, err, test.ShouldBeNil) for i := 0; i < 5; i++ { - _, err = camera.DecodeImageFromCamera(ctx, utils.MimeTypeJPEG, nil, cam) + namedImages, _, err := cam.Images(ctx, nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + _, err = namedImages[0].Image(ctx) 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 995cdbbfa4b..8eae8d3678a 100644 --- a/components/camera/replaypcd/replaypcd.go +++ b/components/camera/replaypcd/replaypcd.go @@ -351,10 +351,6 @@ func (replay *pcdCamera) Stream(ctx context.Context, errHandlers ...gostream.Err return stream, errors.New("Stream is unimplemented") } -func (replay *pcdCamera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return nil, camera.ImageMetadata{}, errors.New("Image is unimplemented") -} - func (replay *pcdCamera) Geometries(ctx context.Context, extra map[string]interface{}) ([]spatialmath.Geometry, error) { return make([]spatialmath.Geometry, 0), nil } diff --git a/components/camera/server.go b/components/camera/server.go index 933a1559536..430df827c0d 100644 --- a/components/camera/server.go +++ b/components/camera/server.go @@ -3,13 +3,11 @@ package camera import ( "context" "fmt" - "sync" "github.com/pkg/errors" "go.opencensus.io/trace" commonpb "go.viam.com/api/common/v1" pb "go.viam.com/api/component/camera/v1" - "google.golang.org/genproto/googleapis/api/httpbody" "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" @@ -22,75 +20,18 @@ import ( // serviceServer implements the CameraService from camera.proto. type serviceServer struct { pb.UnimplementedCameraServiceServer - coll resource.APIResourceGetter[Camera] - - imgTypesMu sync.RWMutex - imgTypes map[string]ImageType - logger logging.Logger + coll resource.APIResourceGetter[Camera] + logger logging.Logger } // NewRPCServiceServer constructs an camera gRPC service server. // It is intentionally untyped to prevent use outside of tests. func NewRPCServiceServer(coll resource.APIResourceGetter[Camera]) interface{} { logger := logging.NewLogger("camserver") - imgTypes := make(map[string]ImageType) return &serviceServer{ - coll: coll, - logger: logger, - imgTypes: imgTypes, - } -} - -// GetImage returns an image from a camera of the underlying robot. If a specific MIME type -// is requested and is not available, an error is returned. -func (s *serviceServer) GetImage( - ctx context.Context, - req *pb.GetImageRequest, -) (*pb.GetImageResponse, error) { - ctx, span := trace.StartSpan(ctx, "camera::server::GetImage") - defer span.End() - cam, err := s.coll.Resource(req.Name) - if err != nil { - return nil, err - } - - // Determine the mimeType we should try to use based on camera properties - if req.MimeType == "" { - s.imgTypesMu.RLock() - imgType, ok := s.imgTypes[req.Name] - s.imgTypesMu.RUnlock() - if !ok { - props, err := cam.Properties(ctx) - if err != nil { - s.logger.CWarnf(ctx, "camera properties not found for %s, assuming color images: %v", req.Name, err) - imgType = ColorStream - } else { - imgType = props.ImageType - } - s.imgTypesMu.Lock() - s.imgTypes[req.Name] = imgType - s.imgTypesMu.Unlock() - } - switch imgType { - case ColorStream, UnspecifiedStream: - req.MimeType = utils.MimeTypeJPEG - case DepthStream: - req.MimeType = utils.MimeTypeRawDepth - default: - req.MimeType = utils.MimeTypeJPEG - } - } - req.MimeType = utils.WithLazyMIMEType(req.MimeType) - - resBytes, resMetadata, err := cam.Image(ctx, req.MimeType, req.Extra.AsMap()) - if err != nil { - return nil, err - } - if len(resBytes) == 0 { - return nil, fmt.Errorf("received empty bytes from Image method of %s", req.Name) + coll: coll, + logger: logger, } - actualMIME, _ := utils.CheckLazyMIMEType(resMetadata.MimeType) - return &pb.GetImageResponse{MimeType: actualMIME, Image: resBytes}, nil } // GetImages returns a list of images and metadata from a camera of the underlying robot. @@ -127,10 +68,8 @@ func (s *serviceServer) GetImages( if err != nil { return nil, errors.Wrap(err, "camera server GetImages could not get the image bytes") } - format := utils.MimeTypeToFormat[img.MimeType()] imgMes := &pb.Image{ SourceName: img.SourceName, - Format: format, MimeType: img.MimeType(), Image: imgBytes, } @@ -145,28 +84,6 @@ func (s *serviceServer) GetImages( return resp, nil } -// RenderFrame renders a frame from a camera of the underlying robot to an HTTP response. A specific MIME type -// can be requested but may not necessarily be the same one returned. -func (s *serviceServer) RenderFrame( - ctx context.Context, - req *pb.RenderFrameRequest, -) (*httpbody.HttpBody, error) { - ctx, span := trace.StartSpan(ctx, "camera::server::RenderFrame") - defer span.End() - if req.MimeType == "" { - req.MimeType = utils.MimeTypeJPEG // default rendering - } - resp, err := s.GetImage(ctx, (*pb.GetImageRequest)(req)) - if err != nil { - return nil, err - } - - return &httpbody.HttpBody{ - ContentType: resp.MimeType, - Data: resp.Image, - }, nil -} - // GetPointCloud returns a frame from a camera of the underlying robot. A specific MIME type // can be requested but may not necessarily be the same one returned. func (s *serviceServer) GetPointCloud( diff --git a/components/camera/server_test.go b/components/camera/server_test.go index 0c2e1882f7e..2d9a953c61f 100644 --- a/components/camera/server_test.go +++ b/components/camera/server_test.go @@ -8,7 +8,6 @@ import ( "image" "image/jpeg" "image/png" - "sync" "testing" "time" @@ -27,7 +26,6 @@ import ( ) var ( - errInvalidMimeType = errors.New("invalid mime type") errGeneratePointCloudFailed = errors.New("can't generate next point cloud") errPropertiesFailed = errors.New("can't get camera properties") errCameraProjectorFailed = errors.New("can't get camera properties") @@ -62,13 +60,6 @@ func TestServer(t *testing.T) { test.That(t, jpeg.Encode(&imgBufJpeg, img, &jpeg.Options{Quality: 75}), test.ShouldBeNil) - imgPng, err := png.Decode(bytes.NewReader(imgBuf.Bytes())) - test.That(t, err, test.ShouldBeNil) - - imgJpeg, err := jpeg.Decode(bytes.NewReader(imgBufJpeg.Bytes())) - - test.That(t, err, test.ShouldBeNil) - var projA transform.Projector intrinsics := &transform.PinholeCameraIntrinsics{ // not the real camera parameters -- fake for test Width: 1280, @@ -132,35 +123,6 @@ func TestServer(t *testing.T) { injectCamera.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - wooMIME := "image/woohoo" - emptyMIME := "image/empty" - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - if mimeType == "" { - mimeType = utils.MimeTypeRawRGBA - } - mimeType, _ = utils.CheckLazyMIMEType(mimeType) - - var respImg image.Image - switch mimeType { - case "", utils.MimeTypeRawRGBA: - respImg = img - case utils.MimeTypePNG: - respImg = imgPng - case utils.MimeTypeJPEG: - respImg = imgJpeg - case wooMIME: - respImg = rimage.NewLazyEncodedImage([]byte{1, 2, 3}, mimeType) - case emptyMIME: - return []byte{}, camera.ImageMetadata{}, nil - default: - return nil, camera.ImageMetadata{}, errInvalidMimeType - } - resBytes, err := rimage.EncodeImage(ctx, respImg, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil - } // depth camera depthImage := rimage.NewEmptyDepthMap(10, 20) depthImage.Set(0, 0, rimage.Depth(40)) @@ -184,16 +146,16 @@ func TestServer(t *testing.T) { injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return projA, nil } - injectCameraDepth.ImageFunc = func( + injectCameraDepth.ImagesFunc = func( ctx context.Context, - mimeType string, + filterSourceNames []string, extra map[string]interface{}, - ) ([]byte, camera.ImageMetadata, error) { - resBytes, err := rimage.EncodeImage(ctx, depthImage, mimeType) + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + namedImg, err := camera.NamedImageFromImage(depthImage, "", utils.MimeTypeRawDepth) if err != nil { - return nil, camera.ImageMetadata{}, err + return nil, resource.ResponseMetadata{}, err } - return resBytes, camera.ImageMetadata{MimeType: mimeType}, nil + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil } // bad camera injectCamera2.NextPointCloudFunc = func(ctx context.Context) (pointcloud.PointCloud, error) { @@ -205,166 +167,14 @@ func TestServer(t *testing.T) { injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) { return nil, errCameraProjectorFailed } - injectCamera2.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return nil, camera.ImageMetadata{}, errGetImageFailed + injectCamera2.ImagesFunc = func( + ctx context.Context, + filterSourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return nil, resource.ResponseMetadata{}, errGetImageFailed } - // does a depth camera transfer its depth image properly - t.Run("GetImage", func(t *testing.T) { - _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{Name: missingCameraName}) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errCameraUnimplemented.Error()) - - // color camera - // ensure that explicit RawRGBA mimetype request will return RawRGBA mimetype response - resp, err := cameraServer.GetImage( - context.Background(), - &pb.GetImageRequest{Name: testCameraName, MimeType: utils.MimeTypeRawRGBA}, - ) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypeRawRGBA) - test.That(t, resp.Image[rimage.RawRGBAHeaderLength:], test.ShouldResemble, img.Pix) - - // ensure that empty mimetype request from color cam will return JPEG mimetype response - resp, err = cameraServer.GetImage( - context.Background(), - &pb.GetImageRequest{Name: testCameraName, MimeType: ""}, - ) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypeJPEG) - test.That(t, resp.Image, test.ShouldNotBeNil) - - // ensure that empty mimetype request from depth cam will return PNG mimetype response - resp, err = cameraServer.GetImage( - context.Background(), - &pb.GetImageRequest{Name: depthCameraName, MimeType: ""}, - ) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypeRawDepth) - test.That(t, resp.Image, test.ShouldNotBeNil) - - resp, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - MimeType: "image/png", - }) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypePNG) - test.That(t, resp.Image, test.ShouldResemble, imgBuf.Bytes()) - - _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - MimeType: "image/who", - }) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errInvalidMimeType.Error()) - - // depth camera - resp, err = cameraServer.GetImage( - context.Background(), - &pb.GetImageRequest{Name: depthCameraName, MimeType: utils.MimeTypePNG}, - ) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypePNG) - test.That(t, resp.Image, test.ShouldNotBeNil) - decodedDepth, err := rimage.DecodeImage( - context.Background(), - resp.Image, - resp.MimeType, - ) - test.That(t, err, test.ShouldBeNil) - dm, err := rimage.ConvertImageToDepthMap(context.Background(), decodedDepth) - test.That(t, err, test.ShouldBeNil) - test.That(t, dm, test.ShouldResemble, depthImage) - - resp, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: depthCameraName, - MimeType: "image/png", - }) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.MimeType, test.ShouldEqual, utils.MimeTypePNG) - test.That(t, resp.Image, test.ShouldResemble, depthBuf.Bytes()) - // bad camera - _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{Name: failCameraName, MimeType: utils.MimeTypeRawRGBA}) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - }) - - t.Run("GetImage response image bytes empty", func(t *testing.T) { - _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - MimeType: emptyMIME, - }) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, "received empty bytes from Image method") - }) - - t.Run("GetImage with lazy", func(t *testing.T) { - // we know its lazy if it's a mime we can't actually handle internally - resp, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - MimeType: wooMIME, - }) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.MimeType, test.ShouldEqual, wooMIME) - test.That(t, resp.Image, test.ShouldResemble, []byte{1, 2, 3}) - - _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - MimeType: "image/notwoo", - }) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errInvalidMimeType.Error()) - }) - - t.Run("GetImage with +lazy default", func(t *testing.T) { - for _, mimeType := range []string{ - utils.MimeTypePNG, - utils.MimeTypeJPEG, - utils.MimeTypeRawRGBA, - } { - req := pb.GetImageRequest{ - Name: testCameraName, - MimeType: mimeType, - } - resp, err := cameraServer.GetImage(context.Background(), &req) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.Image, test.ShouldNotBeNil) - test.That(t, req.MimeType, test.ShouldEqual, utils.WithLazyMIMEType(mimeType)) - } - }) - - t.Run("RenderFrame", func(t *testing.T) { - _, err := cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{Name: missingCameraName}) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errCameraUnimplemented.Error()) - - resp, err := cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{ - Name: testCameraName, - }) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.ContentType, test.ShouldEqual, "image/jpeg") - test.That(t, resp.Data, test.ShouldResemble, imgBufJpeg.Bytes()) - - resp, err = cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{ - Name: testCameraName, - MimeType: "image/png", - }) - test.That(t, err, test.ShouldBeNil) - test.That(t, resp.ContentType, test.ShouldEqual, "image/png") - test.That(t, resp.Data, test.ShouldResemble, imgBuf.Bytes()) - - _, 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()) - - _, err = cameraServer.RenderFrame(context.Background(), &pb.RenderFrameRequest{Name: failCameraName}) - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - }) - t.Run("GetPointCloud", func(t *testing.T) { _, err := cameraServer.GetPointCloud(context.Background(), &pb.GetPointCloudRequest{Name: missingCameraName}) test.That(t, err, test.ShouldNotBeNil) @@ -397,9 +207,9 @@ func TestServer(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, resp.ResponseMetadata.CapturedAt.AsTime(), test.ShouldEqual, time.UnixMilli(12345)) test.That(t, len(resp.Images), test.ShouldEqual, 2) - test.That(t, resp.Images[0].Format, test.ShouldEqual, pb.Format_FORMAT_JPEG) + test.That(t, resp.Images[0].MimeType, test.ShouldEqual, utils.MimeTypeJPEG) test.That(t, resp.Images[0].SourceName, test.ShouldEqual, "color") - test.That(t, resp.Images[1].Format, test.ShouldEqual, pb.Format_FORMAT_RAW_DEPTH) + test.That(t, resp.Images[1].MimeType, test.ShouldEqual, utils.MimeTypeRawDepth) test.That(t, resp.Images[1].SourceName, test.ShouldEqual, "depth") // filter only color @@ -408,7 +218,7 @@ func TestServer(t *testing.T) { test.That(t, resp.ResponseMetadata.CapturedAt.AsTime(), test.ShouldEqual, time.UnixMilli(12345)) test.That(t, len(resp.Images), test.ShouldEqual, 1) test.That(t, resp.Images[0].SourceName, test.ShouldEqual, "color") - test.That(t, resp.Images[0].Format, test.ShouldEqual, pb.Format_FORMAT_JPEG) + test.That(t, resp.Images[0].MimeType, test.ShouldEqual, utils.MimeTypeJPEG) // validate decoded image decodedColor, err := rimage.DecodeImage(context.Background(), resp.Images[0].Image, utils.MimeTypeJPEG) test.That(t, err, test.ShouldBeNil) @@ -421,7 +231,7 @@ func TestServer(t *testing.T) { test.That(t, resp.ResponseMetadata.CapturedAt.AsTime(), test.ShouldEqual, time.UnixMilli(12345)) test.That(t, len(resp.Images), test.ShouldEqual, 1) test.That(t, resp.Images[0].SourceName, test.ShouldEqual, "depth") - test.That(t, resp.Images[0].Format, test.ShouldEqual, pb.Format_FORMAT_RAW_DEPTH) + test.That(t, resp.Images[0].MimeType, test.ShouldEqual, utils.MimeTypeRawDepth) // validate decoded depth map decodedDepthImg, err := rimage.DecodeImage(context.Background(), resp.Images[0].Image, utils.MimeTypeRawDepth) test.That(t, err, test.ShouldBeNil) @@ -445,14 +255,14 @@ func TestServer(t *testing.T) { for _, im := range resp.Images { switch im.SourceName { case "color": - test.That(t, im.Format, test.ShouldEqual, pb.Format_FORMAT_JPEG) + test.That(t, im.MimeType, test.ShouldEqual, utils.MimeTypeJPEG) decoded, err := rimage.DecodeImage(context.Background(), im.Image, utils.MimeTypeJPEG) test.That(t, err, test.ShouldBeNil) test.That(t, decoded.Bounds().Dx(), test.ShouldEqual, 40) test.That(t, decoded.Bounds().Dy(), test.ShouldEqual, 50) seen["color"] = true case "depth": - test.That(t, im.Format, test.ShouldEqual, pb.Format_FORMAT_RAW_DEPTH) + test.That(t, im.MimeType, test.ShouldEqual, utils.MimeTypeRawDepth) decodedDepth, err := rimage.DecodeImage(context.Background(), im.Image, utils.MimeTypeRawDepth) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), decodedDepth) @@ -516,80 +326,6 @@ func TestServer(t *testing.T) { test.That(t, resp2.FrameRate, test.ShouldBeNil) }) - t.Run("GetImage with extra", func(t *testing.T) { - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - test.That(t, extra, test.ShouldBeEmpty) - return nil, camera.ImageMetadata{}, errGetImageFailed - } - - _, err := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - }) - - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - test.That(t, len(extra), test.ShouldEqual, 1) - test.That(t, extra["hello"], test.ShouldEqual, "world") - return nil, camera.ImageMetadata{}, errGetImageFailed - } - - ext, err := goprotoutils.StructToStructPb(map[string]interface{}{"hello": "world"}) - test.That(t, err, test.ShouldBeNil) - - _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - Extra: ext, - }) - - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - test.That(t, len(extra), test.ShouldEqual, 1) - test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - - return nil, camera.ImageMetadata{}, errGetImageFailed - } - - // one kvp created with data.FromDMContextKey - ext, err = goprotoutils.StructToStructPb(map[string]interface{}{data.FromDMString: true}) - test.That(t, err, test.ShouldBeNil) - - _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - Extra: ext, - }) - - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - test.That(t, len(extra), test.ShouldEqual, 2) - test.That(t, extra["hello"], test.ShouldEqual, "world") - test.That(t, extra[data.FromDMString], test.ShouldBeTrue) - return nil, camera.ImageMetadata{}, errGetImageFailed - } - - // use values from data and camera - ext, err = goprotoutils.StructToStructPb( - map[string]interface{}{ - data.FromDMString: true, - "hello": "world", - }, - ) - test.That(t, err, test.ShouldBeNil) - - _, err = cameraServer.GetImage(context.Background(), &pb.GetImageRequest{ - Name: testCameraName, - Extra: ext, - }) - - test.That(t, err, test.ShouldNotBeNil) - test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) - }) - t.Run("GetImages with extra", func(t *testing.T) { injectCamera.ImagesFunc = func( ctx context.Context, @@ -680,25 +416,3 @@ func TestServer(t *testing.T) { test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error()) }) } - -func TestGetImageRace(t *testing.T) { - cameraServer, injectCamera, _, _, err := newServer() - test.That(t, err, test.ShouldBeNil) - - injectCamera.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) { return camera.Properties{}, nil } - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return []byte{1, 2}, camera.ImageMetadata{}, nil - } - var wg sync.WaitGroup - - getImg := func() { - defer wg.Done() - _, retErr := cameraServer.GetImage(context.Background(), &pb.GetImageRequest{Name: testCameraName}) - test.That(t, retErr, test.ShouldBeNil) - } - for range 2 { - wg.Add(1) - go getImg() - } - wg.Wait() -} diff --git a/components/camera/transformpipeline/detector_test.go b/components/camera/transformpipeline/detector_test.go index d4b9203bd78..2470a9cd958 100644 --- a/components/camera/transformpipeline/detector_test.go +++ b/components/camera/transformpipeline/detector_test.go @@ -120,7 +120,10 @@ func TestColorDetectionSource(t *testing.T) { test.That(t, err, test.ShouldBeNil) defer detector.Close(ctx) - resImg, err := camera.DecodeImageFromCamera(ctx, rutils.MimeTypePNG, nil, detector) + namedImages, _, err := detector.Images(ctx, nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + resImg, err := namedImages[0].Image(ctx) test.That(t, err, test.ShouldBeNil) ovImg := rimage.ConvertImage(resImg) test.That(t, ovImg.GetXY(852, 431), test.ShouldResemble, rimage.Red) @@ -145,7 +148,10 @@ func BenchmarkColorDetectionSource(b *testing.B) { b.ResetTimer() // begin benchmarking for i := 0; i < b.N; i++ { - _, _ = camera.DecodeImageFromCamera(ctx, rutils.MimeTypeJPEG, nil, detector) + namedImages, _, _ := detector.Images(ctx, nil, nil) + if len(namedImages) > 0 { + _, _ = namedImages[0].Image(ctx) + } } test.That(b, detector.Close(context.Background()), test.ShouldBeNil) } diff --git a/components/camera/transformpipeline/pipeline.go b/components/camera/transformpipeline/pipeline.go index c0fb0729ee7..0c97584ff0e 100644 --- a/components/camera/transformpipeline/pipeline.go +++ b/components/camera/transformpipeline/pipeline.go @@ -16,7 +16,6 @@ import ( "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" - "go.viam.com/rdk/rimage" "go.viam.com/rdk/rimage/transform" "go.viam.com/rdk/robot" camerautils "go.viam.com/rdk/robot/web/stream/camera" @@ -138,17 +137,20 @@ func newTransformPipeline( return nil, errors.New("pipeline has no transforms in it") } // check if the source produces a depth image or color image - img, err := camera.DecodeImageFromCamera(ctx, "", nil, source) + namedImages, _, err := source.Images(ctx, nil, nil) var streamType camera.ImageType - if err != nil { + if err != nil || len(namedImages) == 0 { streamType = camera.UnspecifiedStream - } else if _, ok := img.(*rimage.DepthMap); ok { - streamType = camera.DepthStream - } else if _, ok := img.(*image.Gray16); ok { - streamType = camera.DepthStream } else { - streamType = camera.ColorStream + img, err := namedImages[0].Image(ctx) + if err != nil { + streamType = camera.UnspecifiedStream + } else if _, ok := img.(*image.Gray16); ok { + streamType = camera.DepthStream + } else { + streamType = camera.ColorStream + } } // loop through the pipeline and create the image flow pipeline := make([]camera.VideoSource, 0, len(cfg.Pipeline)) @@ -189,7 +191,14 @@ 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() - img, err := camera.DecodeImageFromCamera(ctx, "", nil, tp.src) + namedImages, _, err := tp.src.Images(ctx, nil, nil) + if err != nil { + return nil, func() {}, err + } + if len(namedImages) == 0 { + return nil, func() {}, errors.New("no images returned from camera") + } + img, err := namedImages[0].Image(ctx) if err != nil { return nil, func() {}, err } diff --git a/components/camera/transformpipeline/pipeline_test.go b/components/camera/transformpipeline/pipeline_test.go index 6beb96a8637..3841088c26d 100644 --- a/components/camera/transformpipeline/pipeline_test.go +++ b/components/camera/transformpipeline/pipeline_test.go @@ -2,7 +2,6 @@ package transformpipeline import ( "context" - "errors" "testing" "github.com/pion/mediadevices/pkg/prop" @@ -38,7 +37,10 @@ func TestTransformPipelineColor(t *testing.T) { test.That(t, err, test.ShouldBeNil) vs, err := videoSourceFromCamera(context.Background(), src) test.That(t, err, test.ShouldBeNil) - inImg, err := camera.DecodeImageFromCamera(context.Background(), "", nil, src) + namedImages, _, err := src.Images(context.Background(), nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + inImg, err := namedImages[0].Image(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -84,7 +86,10 @@ func TestTransformPipelineDepth(t *testing.T) { source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: dm}, prop.Video{}) src, err := camera.WrapVideoSourceWithProjector(context.Background(), source, nil, camera.DepthStream) test.That(t, err, test.ShouldBeNil) - inImg, err := camera.DecodeImageFromCamera(context.Background(), "", nil, src) + namedImages, _, err := src.Images(context.Background(), nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages) > 0, test.ShouldBeTrue) + inImg, err := namedImages[0].Image(context.Background()) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -207,13 +212,23 @@ func TestTransformPipelineValidateFail(t *testing.T) { func TestVideoSourceFromCameraError(t *testing.T) { malformedCam := &inject.Camera{ - ImageFunc: func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return []byte("not a valid image"), camera.ImageMetadata{MimeType: utils.MimeTypePNG}, nil + ImagesFunc: func( + ctx context.Context, + filterSourceNames []string, + extra map[string]any, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + namedImg, _ := camera.NamedImageFromBytes([]byte("not a valid image"), "", utils.MimeTypePNG) + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil }, } vs, err := videoSourceFromCamera(context.Background(), malformedCam) + test.That(t, err, test.ShouldBeNil) + test.That(t, vs, test.ShouldNotBeNil) + + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + defer stream.Close(context.Background()) + _, _, err = stream.Next(context.Background()) test.That(t, err, test.ShouldNotBeNil) - test.That(t, errors.Is(err, ErrVideoSourceCreation), test.ShouldBeTrue) - test.That(t, vs, test.ShouldBeNil) } diff --git a/components/camera/videosource/webcam.go b/components/camera/videosource/webcam.go index aa749983081..6fd08cf9aea 100644 --- a/components/camera/videosource/webcam.go +++ b/components/camera/videosource/webcam.go @@ -422,31 +422,6 @@ func (c *webcam) ensureActive() error { return nil } -func (c *webcam) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - c.mu.RLock() - defer c.mu.RUnlock() - - if err := c.ensureActive(); err != nil { - return nil, camera.ImageMetadata{}, err - } - if c.reader == nil { - return nil, camera.ImageMetadata{}, errors.New("underlying reader is nil") - } - img, err := c.getLatestFrame() - if err != nil { - return nil, camera.ImageMetadata{}, err - } - - if mimeType == "" { - mimeType = utils.MimeTypeJPEG - } - imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return imgBytes, camera.ImageMetadata{MimeType: mimeType}, nil -} - func (c *webcam) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) { c.mu.RLock() defer c.mu.RUnlock() diff --git a/components/camera/videosourcewrappers.go b/components/camera/videosourcewrappers.go index 7740426c313..ad8bfc1fff9 100644 --- a/components/camera/videosourcewrappers.go +++ b/components/camera/videosourcewrappers.go @@ -213,25 +213,6 @@ func (vs *videoSource) Stream(ctx context.Context, errHandlers ...gostream.Error return vs.videoSource.Stream(ctx, errHandlers...) } -func (vs *videoSource) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) { - if sourceCam, ok := vs.actualSource.(Camera); ok { - return sourceCam.Image(ctx, mimeType, extra) - } - img, release, err := ReadImage(ctx, vs.videoSource) - if err != nil { - return nil, ImageMetadata{}, err - } - defer release() - if mimeType == "" { - mimeType = utils.MimeTypePNG // default to lossless mimetype such as PNG - } - imgBytes, err := rimage.EncodeImage(ctx, img, mimeType) - if err != nil { - return nil, ImageMetadata{}, err - } - return imgBytes, ImageMetadata{MimeType: mimeType}, nil -} - // Images is for getting simultaneous images from different sensors // If the underlying source did not specify an Images function, a default is applied. // The default returns a list of 1 image from ReadImage, and the current time. diff --git a/data/collector_types.go b/data/collector_types.go index 832467b7e81..4627cbb4b73 100644 --- a/data/collector_types.go +++ b/data/collector_types.go @@ -8,7 +8,6 @@ import ( "github.com/pkg/errors" dataPB "go.viam.com/api/app/data/v1" datasyncPB "go.viam.com/api/app/datasync/v1" - camerapb "go.viam.com/api/component/camera/v1" "go.viam.com/utils/protoutils" "google.golang.org/protobuf/types/known/anypb" "google.golang.org/protobuf/types/known/structpb" @@ -276,26 +275,6 @@ func MimeTypeFromProto(mt datasyncPB.MimeType) MimeType { } } -// CameraFormatToMimeType converts a camera camerapb.Format into a MimeType. -func CameraFormatToMimeType(f camerapb.Format) MimeType { - switch f { - case camerapb.Format_FORMAT_UNSPECIFIED: - return MimeTypeUnspecified - case camerapb.Format_FORMAT_JPEG: - return MimeTypeImageJpeg - case camerapb.Format_FORMAT_PNG: - return MimeTypeImagePng - case camerapb.Format_FORMAT_RAW_RGBA: - // TODO: https://viam.atlassian.net/browse/DATA-3497 - fallthrough - case camerapb.Format_FORMAT_RAW_DEPTH: - // TODO: https://viam.atlassian.net/browse/DATA-3497 - fallthrough - default: - return MimeTypeUnspecified - } -} - // MimeTypeStringToMimeType converts a string mime type to a MimeType. func MimeTypeStringToMimeType(mimeType string) MimeType { switch mimeType { @@ -314,18 +293,6 @@ func MimeTypeStringToMimeType(mimeType string) MimeType { } } -// MimeTypeToCameraFormat converts a data.MimeType into a camerapb.Format. -func MimeTypeToCameraFormat(mt MimeType) camerapb.Format { - if mt == MimeTypeImageJpeg { - return camerapb.Format_FORMAT_JPEG - } - - if mt == MimeTypeImagePng { - return camerapb.Format_FORMAT_PNG - } - return camerapb.Format_FORMAT_UNSPECIFIED -} - // Binary represents an element of a binary capture result response. type Binary struct { // Payload contains the binary payload diff --git a/data/collector_types_test.go b/data/collector_types_test.go index c5027357adb..65112e8163d 100644 --- a/data/collector_types_test.go +++ b/data/collector_types_test.go @@ -9,7 +9,6 @@ import ( datasyncPB "go.viam.com/api/app/datasync/v1" commonPB "go.viam.com/api/common/v1" armPB "go.viam.com/api/component/arm/v1" - cameraPB "go.viam.com/api/component/camera/v1" "go.viam.com/test" "google.golang.org/protobuf/types/known/structpb" "google.golang.org/protobuf/types/known/timestamppb" @@ -344,14 +343,6 @@ func TestMimeTypeFromProto(t *testing.T) { test.That(t, MimeTypeFromProto(datasyncPB.MimeType(20)), test.ShouldEqual, MimeTypeUnspecified) } -func TestCameraFormatToMimeType(t *testing.T) { - test.That(t, CameraFormatToMimeType(cameraPB.Format_FORMAT_JPEG), test.ShouldEqual, MimeTypeImageJpeg) - test.That(t, CameraFormatToMimeType(cameraPB.Format_FORMAT_PNG), test.ShouldEqual, MimeTypeImagePng) - test.That(t, CameraFormatToMimeType(cameraPB.Format_FORMAT_RAW_RGBA), test.ShouldEqual, MimeTypeUnspecified) - test.That(t, CameraFormatToMimeType(cameraPB.Format_FORMAT_RAW_DEPTH), test.ShouldEqual, MimeTypeUnspecified) - test.That(t, CameraFormatToMimeType(cameraPB.Format_FORMAT_UNSPECIFIED), test.ShouldEqual, MimeTypeUnspecified) -} - func TestMimeTypeStringToMimeType(t *testing.T) { test.That(t, MimeTypeStringToMimeType(rutils.MimeTypeJPEG), test.ShouldEqual, MimeTypeImageJpeg) test.That(t, MimeTypeStringToMimeType(rutils.MimeTypePNG), test.ShouldEqual, MimeTypeImagePng) diff --git a/go.mod b/go.mod index 5eed1610efa..f0282262dac 100644 --- a/go.mod +++ b/go.mod @@ -465,3 +465,5 @@ require ( github.com/ziutek/mymysql v1.5.4 // indirect golang.org/x/exp v0.0.0-20241009180824-f66d83c29e7c ) + +replace go.viam.com/api => ../sean-api diff --git a/go.sum b/go.sum index c21a32fcc98..377e3c92601 100644 --- a/go.sum +++ b/go.sum @@ -1540,8 +1540,6 @@ go.uber.org/zap v1.18.1/go.mod h1:xg/QME4nWcxGxrpdeYfq7UvYrLh66cuVKdrbD1XF/NI= go.uber.org/zap v1.23.0/go.mod h1:D+nX8jyLsMHMYrln8A0rJjFt/T/9/bGgIhAqxv5URuY= go.uber.org/zap v1.27.0 h1:aJMhYGrd5QSmlpLMr2MftRKl7t8J8PTZPA732ud/XR8= go.uber.org/zap v1.27.0/go.mod h1:GB2qFLM7cTU87MWRP2mPIjqfIDnGu+VIO4V/SdhGo2E= -go.viam.com/api v0.1.477 h1:huAOmn3iejrRapzlYSyB3R0S47itXTUkQ3+kt0Yx02I= -go.viam.com/api v0.1.477/go.mod h1:p/am76zx8SZ74V/F4rEAYQIpHaaLUwJgY2q3Uw3FIWk= go.viam.com/test v1.2.4 h1:JYgZhsuGAQ8sL9jWkziAXN9VJJiKbjoi9BsO33TW3ug= go.viam.com/test v1.2.4/go.mod h1:zI2xzosHdqXAJ/kFqcN+OIF78kQuTV2nIhGZ8EzvaJI= go.viam.com/utils v0.1.170 h1:KSsGNryVDvzdRib10v6/uK3ZYQMtWVnvDMe9+lUv3+M= diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 88121dfebd8..da48c41e229 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -347,8 +347,16 @@ func TestStatusClient(t *testing.T) { var imgBuf bytes.Buffer test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil) - injectCamera.ImageFunc = func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return imgBuf.Bytes(), camera.ImageMetadata{MimeType: rutils.MimeTypePNG}, nil + injectCamera.ImagesFunc = func( + ctx context.Context, + filterSourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + namedImg, err := camera.NamedImageFromBytes(imgBuf.Bytes(), "", rutils.MimeTypePNG) + if err != nil { + return nil, resource.ResponseMetadata{}, err + } + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil } injectInputDev := &inject.InputController{} @@ -523,11 +531,11 @@ func TestStatusClient(t *testing.T) { camera1, err := camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - imgBytes, metadata, err := camera1.Image(context.Background(), rutils.MimeTypeJPEG, nil) + namedImages, metadata, err := camera1.Images(context.Background(), nil, nil) test.That(t, err, test.ShouldNotBeNil) test.That(t, err.Error(), test.ShouldContainSubstring, "not found") - test.That(t, imgBytes, test.ShouldBeNil) - test.That(t, metadata, test.ShouldResemble, camera.ImageMetadata{}) + test.That(t, len(namedImages), test.ShouldEqual, 0) + test.That(t, metadata, test.ShouldResemble, resource.ResponseMetadata{}) gripper1, err := gripper.FromRobot(client, "gripper1") test.That(t, err, test.ShouldBeNil) @@ -604,7 +612,11 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromRobot(client, "camera1") test.That(t, err, test.ShouldBeNil) - frame, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) + namedImages, _, err = camera1.Images(context.Background(), nil, nil) + test.That(t, err, test.ShouldBeNil) + test.That(t, len(namedImages), test.ShouldEqual, 1) + + frame, err := namedImages[0].Image(context.Background()) test.That(t, err, test.ShouldBeNil) compVal, _, err := rimage.CompareImages(img, frame) test.That(t, err, test.ShouldBeNil) diff --git a/robot/impl/local_robot_test.go b/robot/impl/local_robot_test.go index 60402a349c1..74c156759b7 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -89,10 +89,12 @@ func TestConfig1(t *testing.T) { test.That(t, err, test.ShouldBeNil) test.That(t, c1.Name(), test.ShouldResemble, camera.Named("c1")) - pic, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeJPEG, nil, c1) + namedImages, _, err := c1.Images(context.Background(), nil, nil) test.That(t, err, test.ShouldBeNil) - bounds := pic.Bounds() + img, err := namedImages[0].Image(context.Background()) + test.That(t, err, test.ShouldBeNil) + bounds := img.Bounds() test.That(t, bounds.Max.X, test.ShouldBeGreaterThanOrEqualTo, 32) } diff --git a/robot/web/stream/camera/camera.go b/robot/web/stream/camera/camera.go index 6dda774cd80..2b6ea32319c 100644 --- a/robot/web/stream/camera/camera.go +++ b/robot/web/stream/camera/camera.go @@ -10,15 +10,52 @@ import ( "go.viam.com/rdk/components/camera" "go.viam.com/rdk/gostream" + "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" "go.viam.com/rdk/robot" + rutils "go.viam.com/rdk/utils" ) +var streamableImageMIMETypes = map[string]interface{}{ + rutils.MimeTypeRawRGBA: nil, + rutils.MimeTypeRawDepth: nil, + rutils.MimeTypeJPEG: nil, + rutils.MimeTypePNG: nil, + rutils.MimeTypeQOI: nil, +} + +// cropToEvenDimensions crops an image to even dimensions for x264 compatibility. +// x264 only supports even resolutions. This ensures all streamed images work with x264. +func cropToEvenDimensions(img image.Image) (image.Image, error) { + if img, ok := img.(*rimage.LazyEncodedImage); ok { + if err := img.DecodeConfig(); err != nil { + return nil, err + } + } + + hasOddWidth := img.Bounds().Dx()%2 != 0 + hasOddHeight := img.Bounds().Dy()%2 != 0 + if !hasOddWidth && !hasOddHeight { + return img, nil + } + + rImg := rimage.ConvertImage(img) + newWidth := rImg.Width() + newHeight := rImg.Height() + if hasOddWidth { + newWidth-- + } + if hasOddHeight { + newHeight-- + } + return rImg.SubImage(image.Rect(0, 0, newWidth, newHeight)), nil +} + // Camera returns the camera from the robot (derived from the stream) or // an error if it has no camera. func Camera(robot robot.Robot, stream gostream.Stream) (camera.Camera, error) { // Stream names are slightly modified versions of the resource short name - shortName := stream.Name() + shortName := resource.SDPTrackNameToShortName(stream.Name()) cam, err := camera.FromRobot(robot, shortName) if err != nil { return nil, err @@ -26,27 +63,105 @@ func Camera(robot robot.Robot, stream gostream.Stream) (camera.Camera, error) { return cam, nil } +// GetStreamableNamedImageFromCamera returns the first named image it finds from the camera that is supported for streaming. +func GetStreamableNamedImageFromCamera(ctx context.Context, cam camera.Camera) (camera.NamedImage, error) { + namedImages, _, err := cam.Images(ctx, nil, nil) + if err != nil { + return camera.NamedImage{}, err + } + if len(namedImages) == 0 { + return camera.NamedImage{}, fmt.Errorf("no images received for camera %q", cam.Name()) + } + + for _, namedImage := range namedImages { + if _, ok := streamableImageMIMETypes[namedImage.MimeType()]; ok { + return namedImage, nil + } + } + return camera.NamedImage{}, fmt.Errorf("no images were found with a streamable mime type for camera %q", cam.Name()) +} + +// getImageBySourceName retrieves a specific named image from the camera by source name. +func getImageBySourceName(ctx context.Context, cam camera.Camera, sourceName string) (camera.NamedImage, error) { + filterSourceNames := []string{sourceName} + namedImages, _, err := cam.Images(ctx, filterSourceNames, nil) + if err != nil { + return camera.NamedImage{}, err + } + + switch len(namedImages) { + case 0: + return camera.NamedImage{}, fmt.Errorf("no images found for requested source name: %s", sourceName) + case 1: + namedImage := namedImages[0] + if namedImage.SourceName != sourceName { + return camera.NamedImage{}, fmt.Errorf("mismatched source name: requested %q, got %q", sourceName, namedImage.SourceName) + } + return namedImage, nil + default: + // At this point, multiple images were returned. This can happen if the camera is on an older version of the API and does not support + // filtering by source name, or if there is a bug in the camera resource's filtering logic. In this unfortunate case, we'll match the + // requested source name and tank the performance costs. + responseSourceNames := []string{} + for _, namedImage := range namedImages { + if namedImage.SourceName == sourceName { + return namedImage, nil + } + responseSourceNames = append(responseSourceNames, namedImage.SourceName) + } + return camera.NamedImage{}, + fmt.Errorf("no matching source name found for multiple returned images: requested %q, got %q", sourceName, responseSourceNames) + } +} + // VideoSourceFromCamera converts a camera resource into a gostream VideoSource. // This is useful for streaming video from a camera resource. func VideoSourceFromCamera(ctx context.Context, cam camera.Camera) (gostream.VideoSource, error) { + // The reader callback uses a small state machine to determine which image to request from the camera. + // A `sourceName` is used to track the selected image source. On the first call, `sourceName` is nil, + // so the first available streamable image is chosen. On subsequent successful calls, the same `sourceName` + // is used. If any errors occur while getting an image, `sourceName` is reset to nil, and the selection + // process starts over on the next call. This allows the stream to recover if a source becomes unavailable. + var sourceName *string reader := gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - img, err := camera.DecodeImageFromCamera(ctx, "", nil, cam) + var respNamedImage camera.NamedImage + + if sourceName == nil { + namedImage, err := GetStreamableNamedImageFromCamera(ctx, cam) + if err != nil { + return nil, func() {}, err + } + respNamedImage = namedImage + sourceName = &namedImage.SourceName + } else { + var err error + respNamedImage, err = getImageBySourceName(ctx, cam, *sourceName) + if err != nil { + sourceName = nil + return nil, func() {}, err + } + } + + img, err := respNamedImage.Image(ctx) if err != nil { + sourceName = nil return nil, func() {}, err } + + img, err = cropToEvenDimensions(img) + if err != nil { + sourceName = nil + return nil, func() {}, err + } + return img, func() {}, nil }) - img, err := camera.DecodeImageFromCamera(ctx, "", nil, cam) + img, _, err := reader(ctx) if err != nil { // Okay to return empty prop because processInputFrames will tick and set them return gostream.NewVideoSource(reader, prop.Video{}), nil //nolint:nilerr } - if lazyImg, ok := img.(*rimage.LazyEncodedImage); ok { - if err := lazyImg.DecodeConfig(); err != nil { - return nil, fmt.Errorf("failed to decode lazy encoded image: %w", err) - } - } return gostream.NewVideoSource(reader, prop.Video{Width: img.Bounds().Dx(), Height: img.Bounds().Dy()}), nil } diff --git a/robot/web/stream/camera/camera_test.go b/robot/web/stream/camera/camera_test.go index 0e835a4a094..907c2244acb 100644 --- a/robot/web/stream/camera/camera_test.go +++ b/robot/web/stream/camera/camera_test.go @@ -2,25 +2,114 @@ package camera_test import ( "context" + "errors" + "fmt" "image" + "os" "testing" "go.viam.com/test" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" camerautils "go.viam.com/rdk/robot/web/stream/camera" "go.viam.com/rdk/testutils/inject" "go.viam.com/rdk/utils" ) +func TestGetStreamableNamedImageFromCamera(t *testing.T) { + sourceImg := image.NewRGBA(image.Rect(0, 0, 1, 1)) + unstreamableImg, err := camera.NamedImageFromImage(sourceImg, "unstreamable", "image/undefined") + test.That(t, err, test.ShouldBeNil) + streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + t.Run("no images", func(t *testing.T) { + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{}, resource.ResponseMetadata{}, nil + }, + } + _, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeError, errors.New(`no images received for camera "::/"`)) + }) + + t.Run("no streamable images", func(t *testing.T) { + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{unstreamableImg}, resource.ResponseMetadata{}, nil + }, + } + _, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeError, errors.New(`no images were found with a streamable mime type for camera "::/"`)) + }) + + t.Run("one streamable image", func(t *testing.T) { + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{streamableImg}, resource.ResponseMetadata{}, nil + }, + } + img, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + test.That(t, img.SourceName, test.ShouldEqual, "streamable") + }) + + t.Run("first image is not streamable", func(t *testing.T) { + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{unstreamableImg, streamableImg}, resource.ResponseMetadata{}, nil + }, + } + img, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + test.That(t, img.SourceName, test.ShouldEqual, "streamable") + }) + + t.Run("camera Images returns an error", func(t *testing.T) { + expectedErr := errors.New("camera error") + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return nil, resource.ResponseMetadata{}, expectedErr + }, + } + _, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeError, expectedErr) + }) +} + func TestVideoSourceFromCamera(t *testing.T) { - sourceImg := image.NewRGBA(image.Rect(0, 0, 3, 3)) + sourceImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) + namedImg, err := camera.NamedImageFromImage(sourceImg, "test", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) cam := &inject.Camera{ - ImageFunc: func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - imgBytes, err := rimage.EncodeImage(ctx, sourceImg, utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - return imgBytes, camera.ImageMetadata{MimeType: utils.MimeTypePNG}, nil + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil }, } vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) @@ -38,37 +127,564 @@ func TestVideoSourceFromCamera(t *testing.T) { } func TestVideoSourceFromCameraFailure(t *testing.T) { + malformedNamedImage, err := camera.NamedImageFromBytes([]byte("not a valid image"), "source", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) malformedCam := &inject.Camera{ - ImageFunc: func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - return []byte("not a valid image"), camera.ImageMetadata{MimeType: utils.MimeTypePNG}, nil + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{malformedNamedImage}, resource.ResponseMetadata{}, nil }, } vs, err := camerautils.VideoSourceFromCamera(context.Background(), malformedCam) - test.That(t, err, test.ShouldNotBeNil) - expectedErrPrefix := "failed to decode lazy encoded image: " - test.That(t, err.Error(), test.ShouldStartWith, expectedErrPrefix) - test.That(t, vs, test.ShouldBeNil) + test.That(t, err, test.ShouldBeNil) + test.That(t, vs, test.ShouldNotBeNil) + + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New("could not decode image config: image: unknown format")) } func TestVideoSourceFromCameraWithNonsenseMimeType(t *testing.T) { - sourceImg := image.NewRGBA(image.Rect(0, 0, 3, 3)) + sourceImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) + namedImg, err := camera.NamedImageFromImage(sourceImg, "test", "image/undefined") + test.That(t, err, test.ShouldBeNil) camWithNonsenseMimeType := &inject.Camera{ - ImageFunc: func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - imgBytes, err := rimage.EncodeImage(ctx, sourceImg, utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - return imgBytes, camera.ImageMetadata{MimeType: "rand"}, nil + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil }, } - // Should log a warning though due to the nonsense MIME type vs, err := camerautils.VideoSourceFromCamera(context.Background(), camWithNonsenseMimeType) test.That(t, err, test.ShouldBeNil) test.That(t, vs, test.ShouldNotBeNil) - stream, _ := vs.Stream(context.Background()) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New(`no images were found with a streamable mime type for camera "::/"`)) +} + +func TestVideoSourceFromCamera_SourceSelection(t *testing.T) { + sourceImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) + unstreamableImg, err := camera.NamedImageFromImage(sourceImg, "unstreamable", "image/undefined") + test.That(t, err, test.ShouldBeNil) + streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + if len(sourceNames) == 0 { + return []camera.NamedImage{unstreamableImg, streamableImg}, resource.ResponseMetadata{}, nil + } + if len(sourceNames) == 1 && sourceNames[0] == "streamable" { + return []camera.NamedImage{streamableImg}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + img, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + + diffVal, _, err := rimage.CompareImages(img, sourceImg) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) +} + +func TestVideoSourceFromCamera_Recovery(t *testing.T) { + sourceImg1 := image.NewRGBA(image.Rect(0, 0, 4, 4)) + sourceImg2 := image.NewRGBA(image.Rect(0, 0, 6, 6)) + + goodNamedImage, err := camera.NamedImageFromImage(sourceImg1, "good", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + fallbackNamedImage, err := camera.NamedImageFromImage(sourceImg2, "fallback", utils.MimeTypeJPEG) + test.That(t, err, test.ShouldBeNil) + + firstSourceFailed := false + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + if len(sourceNames) == 0 { // GetStreamableNamedImageFromCamera call + if !firstSourceFailed { + return []camera.NamedImage{goodNamedImage}, resource.ResponseMetadata{}, nil + } + return []camera.NamedImage{fallbackNamedImage}, resource.ResponseMetadata{}, nil + } + + // getImageBySourceName call + if sourceNames[0] == "good" { + if !firstSourceFailed { + firstSourceFailed = true + return []camera.NamedImage{goodNamedImage}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, errors.New("source 'good' is gone") + } + if sourceNames[0] == "fallback" { + return []camera.NamedImage{fallbackNamedImage}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unknown source %q", sourceNames[0]) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + // First image should be the good one + img, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + diffVal, _, err := rimage.CompareImages(img, sourceImg1) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) + + // Second call should fail, as the source is now gone. + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New("source 'good' is gone")) + + // Third image should be the fallback one, because the state machine reset. + img, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + diffVal, _, err = rimage.CompareImages(img, sourceImg2) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) +} + +func TestVideoSourceFromCamera_NoImages(t *testing.T) { + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{}, resource.ResponseMetadata{}, nil + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + test.That(t, vs, test.ShouldNotBeNil) + + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New(`no images received for camera "::/"`)) +} + +func TestVideoSourceFromCamera_ImagesError(t *testing.T) { + expectedErr := errors.New("camera error") + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return nil, resource.ResponseMetadata{}, expectedErr + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + test.That(t, vs, test.ShouldNotBeNil) + + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, expectedErr) +} + +func TestVideoSourceFromCamera_MultipleStreamableSources(t *testing.T) { + imageGood1 := image.NewRGBA(image.Rect(0, 0, 4, 4)) + imageGood2 := image.NewRGBA(image.Rect(0, 0, 6, 6)) + namedA, err := camera.NamedImageFromImage(imageGood1, "good1", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + namedB, err := camera.NamedImageFromImage(imageGood2, "good2", utils.MimeTypeJPEG) + test.That(t, err, test.ShouldBeNil) + + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + // When unfiltered, return both streamable sources. Selection should pick good1 first. + if len(sourceNames) == 0 { + return []camera.NamedImage{namedA, namedB}, resource.ResponseMetadata{}, nil + } + // When filtered to good1, return only good1 + if len(sourceNames) == 1 && sourceNames[0] == "good1" { + return []camera.NamedImage{namedA}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + img, _, err := stream.Next(context.Background()) test.That(t, err, test.ShouldBeNil) - test.That(t, img, test.ShouldNotBeNil) + diffVal, _, err := rimage.CompareImages(img, imageGood1) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) +} + +func TestVideoSourceFromCamera_NoStreamableSources(t *testing.T) { + src := image.NewRGBA(image.Rect(0, 0, 2, 2)) + unstream1, err := camera.NamedImageFromImage(src, "bad1", "image/undefined") + test.That(t, err, test.ShouldBeNil) + unstream2, err := camera.NamedImageFromImage(src, "bad2", "image/undefined") + test.That(t, err, test.ShouldBeNil) + + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{unstream1, unstream2}, resource.ResponseMetadata{}, nil + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New(`no images were found with a streamable mime type for camera "::/"`)) +} + +func TestVideoSourceFromCamera_FilterNoImages(t *testing.T) { + src := image.NewRGBA(image.Rect(0, 0, 4, 4)) + good, err := camera.NamedImageFromImage(src, "good", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + fallback, err := camera.NamedImageFromImage(src, "fallback", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + var firstServed bool + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + if len(sourceNames) == 0 { + // Initial selection / or post-reset unfiltered selection + if !firstServed { + return []camera.NamedImage{good, fallback}, resource.ResponseMetadata{}, nil + } + // After the filtered failure, put fallback first so recovery can succeed + return []camera.NamedImage{fallback, good}, resource.ResponseMetadata{}, nil + } + // Filtered to "good": return no images to simulate empty filter result + if len(sourceNames) == 1 && sourceNames[0] == "good" { + firstServed = true + return []camera.NamedImage{}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected sequence: %v", sourceNames) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + // First Next() corresponds to the first filtered read; expect failure + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New("no images found for requested source name: good")) + // Next Next() should recover and serve fallback + img, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + diffVal, _, err := rimage.CompareImages(img, src) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) +} + +func TestVideoSourceFromCamera_FilterMultipleImages(t *testing.T) { + src := image.NewRGBA(image.Rect(0, 0, 4, 4)) + good, err := camera.NamedImageFromImage(src, "good", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + if len(sourceNames) == 0 { + return []camera.NamedImage{good}, resource.ResponseMetadata{}, nil + } + if len(sourceNames) == 1 && sourceNames[0] == "good" { + // Return multiple images even though a single source was requested + // This simulates older camera APIs that don't support filtering + return []camera.NamedImage{good, good}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + // First Next() should succeed, using the first image from the multiple returned images + img, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + diffVal, _, err := rimage.CompareImages(img, src) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) +} + +func TestVideoSourceFromCamera_FilterMultipleImages_NoMatchingSource(t *testing.T) { + src := image.NewRGBA(image.Rect(0, 0, 4, 4)) + img1, err := camera.NamedImageFromImage(src, "source1", utils.MimeTypeRawRGBA) + test.That(t, err, test.ShouldBeNil) + img2, err := camera.NamedImageFromImage(src, "source2", utils.MimeTypeRawRGBA) + test.That(t, err, test.ShouldBeNil) + + var erroredOnce bool + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + // Initial unfiltered call returns two options. The stream will select "source1". + if len(sourceNames) == 0 { + if !erroredOnce { + return []camera.NamedImage{img1, img2}, resource.ResponseMetadata{}, nil + } + // For recovery, only return the second option. + return []camera.NamedImage{img2}, resource.ResponseMetadata{}, nil + } + + // A filtered call for "source1" will return two images that don't match, triggering an error. + if len(sourceNames) == 1 && sourceNames[0] == "source1" { + erroredOnce = true + return []camera.NamedImage{img2, img2}, resource.ResponseMetadata{}, nil + } + + // The filtered call for "source2" is used for a successful recovery. + if len(sourceNames) == 1 && sourceNames[0] == "source2" { + return []camera.NamedImage{img2}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + // The first call to `VideoSourceFromCamera` will select "source1". The first call to `stream.Next()` + // will then request "source1" and receive two "source2" images, causing an error. + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, + errors.New(`no matching source name found for multiple returned images: requested "source1", got ["source2" "source2"]`)) + + // On the next call, the stream should recover by performing an unfiltered images call. + // The mock will return only the second image, and the stream should succeed. + img, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + diffVal, _, err := rimage.CompareImages(img, src) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) + + // Subsequent calls should also succeed. + img, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + diffVal, _, err = rimage.CompareImages(img, src) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) +} + +func TestVideoSourceFromCamera_LazyDecodeConfigError(t *testing.T) { + malformedImage := rimage.NewLazyEncodedImage( + []byte("not a valid image"), + utils.MimeTypePNG, + ) + + namedImg, err := camera.NamedImageFromImage(malformedImage, "lazy-image", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil + }, + } + + _, err = camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) +} + +func TestVideoSourceFromCamera_InvalidImageFirst_ThenValidAlsoAvailable(t *testing.T) { + validImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) + invalidBytes := []byte("not a valid image") + invalidNamed, err := camera.NamedImageFromBytes(invalidBytes, "bad", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + validNamed, err := camera.NamedImageFromImage(validImg, "good", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + // Unfiltered call returns a valid combination, but first entry is invalid + if len(sourceNames) == 0 { + return []camera.NamedImage{invalidNamed, validNamed}, resource.ResponseMetadata{}, nil + } + // If filtered to bad, still bad + if len(sourceNames) == 1 && sourceNames[0] == "bad" { + return []camera.NamedImage{invalidNamed}, resource.ResponseMetadata{}, nil + } + // If filtered to good, return the good one + if len(sourceNames) == 1 && sourceNames[0] == "good" { + return []camera.NamedImage{validNamed}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected filter: %v", sourceNames) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + // First Next(): already failed, and unfiltered selection again chooses invalid first -> fail + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New("could not decode image config: image: unknown format")) + // Second Next(): still fails because selection continues to prioritize invalid-first combination + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New("could not decode image config: image: unknown format")) +} + +func TestVideoSourceFromCamera_FilterMismatchedSourceName(t *testing.T) { + src := image.NewRGBA(image.Rect(0, 0, 4, 4)) + good, err := camera.NamedImageFromImage(src, "good", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + mismatched, err := camera.NamedImageFromImage(src, "bad", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + var askedOnce bool + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + if len(sourceNames) == 0 { + return []camera.NamedImage{good}, resource.ResponseMetadata{}, nil + } + if len(sourceNames) == 1 && sourceNames[0] == "good" { + if !askedOnce { + askedOnce = true + // Return a single image with a different source name than requested + return []camera.NamedImage{mismatched}, resource.ResponseMetadata{}, nil + } + // After reset, success + return []camera.NamedImage{good}, resource.ResponseMetadata{}, nil + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected filter: %v", sourceNames) + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + // First Next(): filtered mismatch should fail + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New(`mismatched source name: requested "good", got "bad"`)) + // Second Next(): should recover and deliver the correct image + img, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + diffVal, _, err := rimage.CompareImages(img, src) + test.That(t, err, test.ShouldBeNil) + test.That(t, diffVal, test.ShouldEqual, 0) +} + +func TestVideoSourceFromCamera_OddDimensionsCropped(t *testing.T) { + // Create an image with odd dimensions + oddImg := image.NewRGBA(image.Rect(0, 0, 3, 3)) + + namedImg, err := camera.NamedImageFromImage(oddImg, "test", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil + }, + } + + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + + stream, err := vs.Stream(context.Background()) + test.That(t, err, test.ShouldBeNil) + + streamedImg, _, err := stream.Next(context.Background()) + test.That(t, err, test.ShouldBeNil) + + // Verify dimensions were cropped from 3x3 to 2x2 for x264 compatibility + test.That(t, streamedImg.Bounds(), test.ShouldResemble, image.Rect(0, 0, 2, 2)) +} + +// TODO(https://viam.atlassian.net/browse/RSDK-11726): Remove this test. +func TestGetImagesInStreamServerEnvVar(t *testing.T) { + ogVal, ok := os.LookupEnv(utils.GetImagesInStreamServerEnvVar) + if ok { + defer os.Setenv(utils.GetImagesInStreamServerEnvVar, ogVal) + } else { + defer os.Unsetenv(utils.GetImagesInStreamServerEnvVar) + } + + t.Run("when env var is set to true, returns true", func(t *testing.T) { + os.Setenv(utils.GetImagesInStreamServerEnvVar, "true") + test.That(t, utils.GetImagesInStreamServer(), test.ShouldBeTrue) + }) + + t.Run("when env var is not set, returns false", func(t *testing.T) { + os.Unsetenv(utils.GetImagesInStreamServerEnvVar) + test.That(t, utils.GetImagesInStreamServer(), test.ShouldBeFalse) + }) } diff --git a/robot/web/stream/camera2/camera.go b/robot/web/stream/camera2/camera.go deleted file mode 100644 index 2b6ea32319c..00000000000 --- a/robot/web/stream/camera2/camera.go +++ /dev/null @@ -1,167 +0,0 @@ -// Package camera provides utilities for working with camera resources in the context of streaming. -package camera - -import ( - "context" - "fmt" - "image" - - "github.com/pion/mediadevices/pkg/prop" - - "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/gostream" - "go.viam.com/rdk/resource" - "go.viam.com/rdk/rimage" - "go.viam.com/rdk/robot" - rutils "go.viam.com/rdk/utils" -) - -var streamableImageMIMETypes = map[string]interface{}{ - rutils.MimeTypeRawRGBA: nil, - rutils.MimeTypeRawDepth: nil, - rutils.MimeTypeJPEG: nil, - rutils.MimeTypePNG: nil, - rutils.MimeTypeQOI: nil, -} - -// cropToEvenDimensions crops an image to even dimensions for x264 compatibility. -// x264 only supports even resolutions. This ensures all streamed images work with x264. -func cropToEvenDimensions(img image.Image) (image.Image, error) { - if img, ok := img.(*rimage.LazyEncodedImage); ok { - if err := img.DecodeConfig(); err != nil { - return nil, err - } - } - - hasOddWidth := img.Bounds().Dx()%2 != 0 - hasOddHeight := img.Bounds().Dy()%2 != 0 - if !hasOddWidth && !hasOddHeight { - return img, nil - } - - rImg := rimage.ConvertImage(img) - newWidth := rImg.Width() - newHeight := rImg.Height() - if hasOddWidth { - newWidth-- - } - if hasOddHeight { - newHeight-- - } - return rImg.SubImage(image.Rect(0, 0, newWidth, newHeight)), nil -} - -// Camera returns the camera from the robot (derived from the stream) or -// an error if it has no camera. -func Camera(robot robot.Robot, stream gostream.Stream) (camera.Camera, error) { - // Stream names are slightly modified versions of the resource short name - shortName := resource.SDPTrackNameToShortName(stream.Name()) - cam, err := camera.FromRobot(robot, shortName) - if err != nil { - return nil, err - } - return cam, nil -} - -// GetStreamableNamedImageFromCamera returns the first named image it finds from the camera that is supported for streaming. -func GetStreamableNamedImageFromCamera(ctx context.Context, cam camera.Camera) (camera.NamedImage, error) { - namedImages, _, err := cam.Images(ctx, nil, nil) - if err != nil { - return camera.NamedImage{}, err - } - if len(namedImages) == 0 { - return camera.NamedImage{}, fmt.Errorf("no images received for camera %q", cam.Name()) - } - - for _, namedImage := range namedImages { - if _, ok := streamableImageMIMETypes[namedImage.MimeType()]; ok { - return namedImage, nil - } - } - return camera.NamedImage{}, fmt.Errorf("no images were found with a streamable mime type for camera %q", cam.Name()) -} - -// getImageBySourceName retrieves a specific named image from the camera by source name. -func getImageBySourceName(ctx context.Context, cam camera.Camera, sourceName string) (camera.NamedImage, error) { - filterSourceNames := []string{sourceName} - namedImages, _, err := cam.Images(ctx, filterSourceNames, nil) - if err != nil { - return camera.NamedImage{}, err - } - - switch len(namedImages) { - case 0: - return camera.NamedImage{}, fmt.Errorf("no images found for requested source name: %s", sourceName) - case 1: - namedImage := namedImages[0] - if namedImage.SourceName != sourceName { - return camera.NamedImage{}, fmt.Errorf("mismatched source name: requested %q, got %q", sourceName, namedImage.SourceName) - } - return namedImage, nil - default: - // At this point, multiple images were returned. This can happen if the camera is on an older version of the API and does not support - // filtering by source name, or if there is a bug in the camera resource's filtering logic. In this unfortunate case, we'll match the - // requested source name and tank the performance costs. - responseSourceNames := []string{} - for _, namedImage := range namedImages { - if namedImage.SourceName == sourceName { - return namedImage, nil - } - responseSourceNames = append(responseSourceNames, namedImage.SourceName) - } - return camera.NamedImage{}, - fmt.Errorf("no matching source name found for multiple returned images: requested %q, got %q", sourceName, responseSourceNames) - } -} - -// VideoSourceFromCamera converts a camera resource into a gostream VideoSource. -// This is useful for streaming video from a camera resource. -func VideoSourceFromCamera(ctx context.Context, cam camera.Camera) (gostream.VideoSource, error) { - // The reader callback uses a small state machine to determine which image to request from the camera. - // A `sourceName` is used to track the selected image source. On the first call, `sourceName` is nil, - // so the first available streamable image is chosen. On subsequent successful calls, the same `sourceName` - // is used. If any errors occur while getting an image, `sourceName` is reset to nil, and the selection - // process starts over on the next call. This allows the stream to recover if a source becomes unavailable. - var sourceName *string - reader := gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) { - var respNamedImage camera.NamedImage - - if sourceName == nil { - namedImage, err := GetStreamableNamedImageFromCamera(ctx, cam) - if err != nil { - return nil, func() {}, err - } - respNamedImage = namedImage - sourceName = &namedImage.SourceName - } else { - var err error - respNamedImage, err = getImageBySourceName(ctx, cam, *sourceName) - if err != nil { - sourceName = nil - return nil, func() {}, err - } - } - - img, err := respNamedImage.Image(ctx) - if err != nil { - sourceName = nil - return nil, func() {}, err - } - - img, err = cropToEvenDimensions(img) - if err != nil { - sourceName = nil - return nil, func() {}, err - } - - return img, func() {}, nil - }) - - img, _, err := reader(ctx) - if err != nil { - // Okay to return empty prop because processInputFrames will tick and set them - return gostream.NewVideoSource(reader, prop.Video{}), nil //nolint:nilerr - } - - return gostream.NewVideoSource(reader, prop.Video{Width: img.Bounds().Dx(), Height: img.Bounds().Dy()}), nil -} diff --git a/robot/web/stream/camera2/camera_test.go b/robot/web/stream/camera2/camera_test.go deleted file mode 100644 index 12c3b148e30..00000000000 --- a/robot/web/stream/camera2/camera_test.go +++ /dev/null @@ -1,690 +0,0 @@ -package camera_test - -import ( - "context" - "errors" - "fmt" - "image" - "os" - "testing" - - "go.viam.com/test" - - "go.viam.com/rdk/components/camera" - "go.viam.com/rdk/resource" - "go.viam.com/rdk/rimage" - camerautils "go.viam.com/rdk/robot/web/stream/camera2" - "go.viam.com/rdk/testutils/inject" - "go.viam.com/rdk/utils" -) - -func TestGetStreamableNamedImageFromCamera(t *testing.T) { - sourceImg := image.NewRGBA(image.Rect(0, 0, 1, 1)) - unstreamableImg, err := camera.NamedImageFromImage(sourceImg, "unstreamable", "image/undefined") - test.That(t, err, test.ShouldBeNil) - streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - t.Run("no images", func(t *testing.T) { - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{}, resource.ResponseMetadata{}, nil - }, - } - _, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeError, errors.New(`no images received for camera "::/"`)) - }) - - t.Run("no streamable images", func(t *testing.T) { - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{unstreamableImg}, resource.ResponseMetadata{}, nil - }, - } - _, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeError, errors.New(`no images were found with a streamable mime type for camera "::/"`)) - }) - - t.Run("one streamable image", func(t *testing.T) { - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{streamableImg}, resource.ResponseMetadata{}, nil - }, - } - img, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - test.That(t, img.SourceName, test.ShouldEqual, "streamable") - }) - - t.Run("first image is not streamable", func(t *testing.T) { - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{unstreamableImg, streamableImg}, resource.ResponseMetadata{}, nil - }, - } - img, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - test.That(t, img.SourceName, test.ShouldEqual, "streamable") - }) - - t.Run("camera Images returns an error", func(t *testing.T) { - expectedErr := errors.New("camera error") - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return nil, resource.ResponseMetadata{}, expectedErr - }, - } - _, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeError, expectedErr) - }) -} - -func TestVideoSourceFromCamera(t *testing.T) { - sourceImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) - namedImg, err := camera.NamedImageFromImage(sourceImg, "test", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil - }, - } - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - - diffVal, _, err := rimage.CompareImages(img, sourceImg) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCameraFailure(t *testing.T) { - malformedNamedImage, err := camera.NamedImageFromBytes([]byte("not a valid image"), "source", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - malformedCam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{malformedNamedImage}, resource.ResponseMetadata{}, nil - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), malformedCam) - test.That(t, err, test.ShouldBeNil) - test.That(t, vs, test.ShouldNotBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New("could not decode image config: image: unknown format")) -} - -func TestVideoSourceFromCameraWithNonsenseMimeType(t *testing.T) { - sourceImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) - namedImg, err := camera.NamedImageFromImage(sourceImg, "test", "image/undefined") - test.That(t, err, test.ShouldBeNil) - - camWithNonsenseMimeType := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), camWithNonsenseMimeType) - test.That(t, err, test.ShouldBeNil) - test.That(t, vs, test.ShouldNotBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New(`no images were found with a streamable mime type for camera "::/"`)) -} - -func TestVideoSourceFromCamera_SourceSelection(t *testing.T) { - sourceImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) - unstreamableImg, err := camera.NamedImageFromImage(sourceImg, "unstreamable", "image/undefined") - test.That(t, err, test.ShouldBeNil) - streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - if len(sourceNames) == 0 { - return []camera.NamedImage{unstreamableImg, streamableImg}, resource.ResponseMetadata{}, nil - } - if len(sourceNames) == 1 && sourceNames[0] == "streamable" { - return []camera.NamedImage{streamableImg}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - - diffVal, _, err := rimage.CompareImages(img, sourceImg) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCamera_Recovery(t *testing.T) { - sourceImg1 := image.NewRGBA(image.Rect(0, 0, 4, 4)) - sourceImg2 := image.NewRGBA(image.Rect(0, 0, 6, 6)) - - goodNamedImage, err := camera.NamedImageFromImage(sourceImg1, "good", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - fallbackNamedImage, err := camera.NamedImageFromImage(sourceImg2, "fallback", utils.MimeTypeJPEG) - test.That(t, err, test.ShouldBeNil) - - firstSourceFailed := false - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - if len(sourceNames) == 0 { // GetStreamableNamedImageFromCamera call - if !firstSourceFailed { - return []camera.NamedImage{goodNamedImage}, resource.ResponseMetadata{}, nil - } - return []camera.NamedImage{fallbackNamedImage}, resource.ResponseMetadata{}, nil - } - - // getImageBySourceName call - if sourceNames[0] == "good" { - if !firstSourceFailed { - firstSourceFailed = true - return []camera.NamedImage{goodNamedImage}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, errors.New("source 'good' is gone") - } - if sourceNames[0] == "fallback" { - return []camera.NamedImage{fallbackNamedImage}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unknown source %q", sourceNames[0]) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - // First image should be the good one - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err := rimage.CompareImages(img, sourceImg1) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) - - // Second call should fail, as the source is now gone. - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New("source 'good' is gone")) - - // Third image should be the fallback one, because the state machine reset. - img, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err = rimage.CompareImages(img, sourceImg2) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCamera_NoImages(t *testing.T) { - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{}, resource.ResponseMetadata{}, nil - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - test.That(t, vs, test.ShouldNotBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New(`no images received for camera "::/"`)) -} - -func TestVideoSourceFromCamera_ImagesError(t *testing.T) { - expectedErr := errors.New("camera error") - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return nil, resource.ResponseMetadata{}, expectedErr - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - test.That(t, vs, test.ShouldNotBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, expectedErr) -} - -func TestVideoSourceFromCamera_MultipleStreamableSources(t *testing.T) { - imageGood1 := image.NewRGBA(image.Rect(0, 0, 4, 4)) - imageGood2 := image.NewRGBA(image.Rect(0, 0, 6, 6)) - namedA, err := camera.NamedImageFromImage(imageGood1, "good1", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - namedB, err := camera.NamedImageFromImage(imageGood2, "good2", utils.MimeTypeJPEG) - test.That(t, err, test.ShouldBeNil) - - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - // When unfiltered, return both streamable sources. Selection should pick good1 first. - if len(sourceNames) == 0 { - return []camera.NamedImage{namedA, namedB}, resource.ResponseMetadata{}, nil - } - // When filtered to good1, return only good1 - if len(sourceNames) == 1 && sourceNames[0] == "good1" { - return []camera.NamedImage{namedA}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err := rimage.CompareImages(img, imageGood1) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCamera_NoStreamableSources(t *testing.T) { - src := image.NewRGBA(image.Rect(0, 0, 2, 2)) - unstream1, err := camera.NamedImageFromImage(src, "bad1", "image/undefined") - test.That(t, err, test.ShouldBeNil) - unstream2, err := camera.NamedImageFromImage(src, "bad2", "image/undefined") - test.That(t, err, test.ShouldBeNil) - - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{unstream1, unstream2}, resource.ResponseMetadata{}, nil - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New(`no images were found with a streamable mime type for camera "::/"`)) -} - -func TestVideoSourceFromCamera_FilterNoImages(t *testing.T) { - src := image.NewRGBA(image.Rect(0, 0, 4, 4)) - good, err := camera.NamedImageFromImage(src, "good", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - fallback, err := camera.NamedImageFromImage(src, "fallback", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - var firstServed bool - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - if len(sourceNames) == 0 { - // Initial selection / or post-reset unfiltered selection - if !firstServed { - return []camera.NamedImage{good, fallback}, resource.ResponseMetadata{}, nil - } - // After the filtered failure, put fallback first so recovery can succeed - return []camera.NamedImage{fallback, good}, resource.ResponseMetadata{}, nil - } - // Filtered to "good": return no images to simulate empty filter result - if len(sourceNames) == 1 && sourceNames[0] == "good" { - firstServed = true - return []camera.NamedImage{}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected sequence: %v", sourceNames) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - // First Next() corresponds to the first filtered read; expect failure - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New("no images found for requested source name: good")) - // Next Next() should recover and serve fallback - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err := rimage.CompareImages(img, src) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCamera_FilterMultipleImages(t *testing.T) { - src := image.NewRGBA(image.Rect(0, 0, 4, 4)) - good, err := camera.NamedImageFromImage(src, "good", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - if len(sourceNames) == 0 { - return []camera.NamedImage{good}, resource.ResponseMetadata{}, nil - } - if len(sourceNames) == 1 && sourceNames[0] == "good" { - // Return multiple images even though a single source was requested - // This simulates older camera APIs that don't support filtering - return []camera.NamedImage{good, good}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - // First Next() should succeed, using the first image from the multiple returned images - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err := rimage.CompareImages(img, src) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCamera_FilterMultipleImages_NoMatchingSource(t *testing.T) { - src := image.NewRGBA(image.Rect(0, 0, 4, 4)) - img1, err := camera.NamedImageFromImage(src, "source1", utils.MimeTypeRawRGBA) - test.That(t, err, test.ShouldBeNil) - img2, err := camera.NamedImageFromImage(src, "source2", utils.MimeTypeRawRGBA) - test.That(t, err, test.ShouldBeNil) - - var erroredOnce bool - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - // Initial unfiltered call returns two options. The stream will select "source1". - if len(sourceNames) == 0 { - if !erroredOnce { - return []camera.NamedImage{img1, img2}, resource.ResponseMetadata{}, nil - } - // For recovery, only return the second option. - return []camera.NamedImage{img2}, resource.ResponseMetadata{}, nil - } - - // A filtered call for "source1" will return two images that don't match, triggering an error. - if len(sourceNames) == 1 && sourceNames[0] == "source1" { - erroredOnce = true - return []camera.NamedImage{img2, img2}, resource.ResponseMetadata{}, nil - } - - // The filtered call for "source2" is used for a successful recovery. - if len(sourceNames) == 1 && sourceNames[0] == "source2" { - return []camera.NamedImage{img2}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected source filter: %v", sourceNames) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - // The first call to `VideoSourceFromCamera` will select "source1". The first call to `stream.Next()` - // will then request "source1" and receive two "source2" images, causing an error. - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, - errors.New(`no matching source name found for multiple returned images: requested "source1", got ["source2" "source2"]`)) - - // On the next call, the stream should recover by performing an unfiltered images call. - // The mock will return only the second image, and the stream should succeed. - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err := rimage.CompareImages(img, src) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) - - // Subsequent calls should also succeed. - img, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err = rimage.CompareImages(img, src) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCamera_LazyDecodeConfigError(t *testing.T) { - malformedImage := rimage.NewLazyEncodedImage( - []byte("not a valid image"), - utils.MimeTypePNG, - ) - - namedImg, err := camera.NamedImageFromImage(malformedImage, "lazy-image", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil - }, - } - - _, err = camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) -} - -func TestVideoSourceFromCamera_InvalidImageFirst_ThenValidAlsoAvailable(t *testing.T) { - validImg := image.NewRGBA(image.Rect(0, 0, 4, 4)) - invalidBytes := []byte("not a valid image") - invalidNamed, err := camera.NamedImageFromBytes(invalidBytes, "bad", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - validNamed, err := camera.NamedImageFromImage(validImg, "good", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - // Unfiltered call returns a valid combination, but first entry is invalid - if len(sourceNames) == 0 { - return []camera.NamedImage{invalidNamed, validNamed}, resource.ResponseMetadata{}, nil - } - // If filtered to bad, still bad - if len(sourceNames) == 1 && sourceNames[0] == "bad" { - return []camera.NamedImage{invalidNamed}, resource.ResponseMetadata{}, nil - } - // If filtered to good, return the good one - if len(sourceNames) == 1 && sourceNames[0] == "good" { - return []camera.NamedImage{validNamed}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected filter: %v", sourceNames) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - // First Next(): already failed, and unfiltered selection again chooses invalid first -> fail - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New("could not decode image config: image: unknown format")) - // Second Next(): still fails because selection continues to prioritize invalid-first combination - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New("could not decode image config: image: unknown format")) -} - -func TestVideoSourceFromCamera_FilterMismatchedSourceName(t *testing.T) { - src := image.NewRGBA(image.Rect(0, 0, 4, 4)) - good, err := camera.NamedImageFromImage(src, "good", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - mismatched, err := camera.NamedImageFromImage(src, "bad", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - var askedOnce bool - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - if len(sourceNames) == 0 { - return []camera.NamedImage{good}, resource.ResponseMetadata{}, nil - } - if len(sourceNames) == 1 && sourceNames[0] == "good" { - if !askedOnce { - askedOnce = true - // Return a single image with a different source name than requested - return []camera.NamedImage{mismatched}, resource.ResponseMetadata{}, nil - } - // After reset, success - return []camera.NamedImage{good}, resource.ResponseMetadata{}, nil - } - return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected filter: %v", sourceNames) - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - // First Next(): filtered mismatch should fail - _, _, err = stream.Next(context.Background()) - test.That(t, err, test.ShouldBeError, errors.New(`mismatched source name: requested "good", got "bad"`)) - // Second Next(): should recover and deliver the correct image - img, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - diffVal, _, err := rimage.CompareImages(img, src) - test.That(t, err, test.ShouldBeNil) - test.That(t, diffVal, test.ShouldEqual, 0) -} - -func TestVideoSourceFromCamera_OddDimensionsCropped(t *testing.T) { - // Create an image with odd dimensions - oddImg := image.NewRGBA(image.Rect(0, 0, 3, 3)) - - namedImg, err := camera.NamedImageFromImage(oddImg, "test", utils.MimeTypePNG) - test.That(t, err, test.ShouldBeNil) - - cam := &inject.Camera{ - ImagesFunc: func( - ctx context.Context, - sourceNames []string, - extra map[string]interface{}, - ) ([]camera.NamedImage, resource.ResponseMetadata, error) { - return []camera.NamedImage{namedImg}, resource.ResponseMetadata{}, nil - }, - } - - vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) - test.That(t, err, test.ShouldBeNil) - - stream, err := vs.Stream(context.Background()) - test.That(t, err, test.ShouldBeNil) - - streamedImg, _, err := stream.Next(context.Background()) - test.That(t, err, test.ShouldBeNil) - - // Verify dimensions were cropped from 3x3 to 2x2 for x264 compatibility - test.That(t, streamedImg.Bounds(), test.ShouldResemble, image.Rect(0, 0, 2, 2)) -} - -// TODO(https://viam.atlassian.net/browse/RSDK-11726): Remove this test. -func TestGetImagesInStreamServerEnvVar(t *testing.T) { - ogVal, ok := os.LookupEnv(utils.GetImagesInStreamServerEnvVar) - if ok { - defer os.Setenv(utils.GetImagesInStreamServerEnvVar, ogVal) - } else { - defer os.Unsetenv(utils.GetImagesInStreamServerEnvVar) - } - - t.Run("when env var is set to true, returns true", func(t *testing.T) { - os.Setenv(utils.GetImagesInStreamServerEnvVar, "true") - test.That(t, utils.GetImagesInStreamServer(), test.ShouldBeTrue) - }) - - t.Run("when env var is not set, returns false", func(t *testing.T) { - os.Unsetenv(utils.GetImagesInStreamServerEnvVar) - test.That(t, utils.GetImagesInStreamServer(), test.ShouldBeFalse) - }) -} diff --git a/robot/web/stream/server.go b/robot/web/stream/server.go index 65104f4fcd2..721959d818e 100644 --- a/robot/web/stream/server.go +++ b/robot/web/stream/server.go @@ -22,8 +22,7 @@ import ( "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" "go.viam.com/rdk/robot" - camerautils1 "go.viam.com/rdk/robot/web/stream/camera" - camerautils2 "go.viam.com/rdk/robot/web/stream/camera2" + camerautils "go.viam.com/rdk/robot/web/stream/camera" "go.viam.com/rdk/robot/web/stream/state" rutils "go.viam.com/rdk/utils" ) @@ -172,7 +171,7 @@ func (server *Server) AddStream(ctx context.Context, req *streampb.AddStreamRequ } // return error if resource is neither a camera nor audioinput - _, isCamErr := cameraUtilsCamera(server.robot, streamStateToAdd.Stream) + _, isCamErr := camerautils.Camera(server.robot, streamStateToAdd.Stream) _, isAudioErr := audioinput.FromRobot(server.robot, streamStateToAdd.Stream.Name()) if isCamErr != nil && isAudioErr != nil { return nil, errors.Errorf("stream is neither a camera nor audioinput. streamName: %v", streamStateToAdd.Stream) @@ -273,7 +272,7 @@ func (server *Server) RemoveStream(ctx context.Context, req *streampb.RemoveStre streamName := streamToRemove.Stream.Name() _, isAudioResourceErr := audioinput.FromRobot(server.robot, streamName) - _, isCameraResourceErr := cameraUtilsCamera(server.robot, streamToRemove.Stream) + _, isCameraResourceErr := camerautils.Camera(server.robot, streamToRemove.Stream) if isAudioResourceErr != nil && isCameraResourceErr != nil { return &streampb.RemoveStreamResponse{}, nil @@ -413,7 +412,7 @@ func (server *Server) resizeVideoSource(ctx context.Context, name string, width, if !ok { return fmt.Errorf("stream state not found with name %q", name) } - vs, err := cameraUtilsVideoSourceFromCamera(ctx, cam) + vs, err := camerautils.VideoSourceFromCamera(ctx, cam) if err != nil { return fmt.Errorf("failed to create video source from camera: %w", err) } @@ -445,7 +444,7 @@ func (server *Server) resetVideoSource(ctx context.Context, name string) error { return fmt.Errorf("stream state not found with name %q", name) } server.logger.Debug("resetting video source") - vs, err := cameraUtilsVideoSourceFromCamera(ctx, cam) + vs, err := camerautils.VideoSourceFromCamera(ctx, cam) if err != nil { return fmt.Errorf("failed to create video source from camera: %w", err) } @@ -637,7 +636,7 @@ func (server *Server) refreshVideoSources(ctx context.Context) { if err != nil { continue } - src, err := cameraUtilsVideoSourceFromCamera(ctx, cam) + src, err := camerautils.VideoSourceFromCamera(ctx, cam) if err != nil { server.logger.Errorf("error creating video source from camera: %v", err) continue @@ -788,20 +787,6 @@ func GenerateResolutions(width, height int32, logger logging.Logger) []Resolutio return resolutions } -func cameraUtilsCamera(robot robot.Robot, stream gostream.Stream) (camera.Camera, error) { - if rutils.GetImagesInStreamServer() { - return camerautils2.Camera(robot, stream) - } - return camerautils1.Camera(robot, stream) -} - -func cameraUtilsVideoSourceFromCamera(ctx context.Context, cam camera.Camera) (gostream.VideoSource, error) { - if rutils.GetImagesInStreamServer() { - return camerautils2.VideoSourceFromCamera(ctx, cam) - } - return camerautils1.VideoSourceFromCamera(ctx, cam) -} - // sampleFrameSize takes in a camera.Camera, starts a stream, attempts to // pull a frame, and returns the width and height. func sampleFrameSize(ctx context.Context, cam camera.Camera, logger logging.Logger) (int, int, error) { @@ -823,9 +808,16 @@ retryLoop: case <-ctx.Done(): return 0, 0, ctx.Err() default: - frame, err = camera.DecodeImageFromCamera(ctx, "", nil, cam) - if err == nil { - break retryLoop // Break out of the for loop, not just the select. + namedImages, _, imgErr := cam.Images(ctx, nil, nil) + if imgErr == nil && len(namedImages) > 0 { + frame, err = namedImages[0].Image(ctx) + if err == nil { + break retryLoop // Break out of the for loop, not just the select. + } + } else if imgErr != nil { + err = imgErr + } else { + err = fmt.Errorf("no images returned from camera") } logger.Debugf("failed to get frame, retrying... (%d/5)", i+1) time.Sleep(retryDelay) @@ -848,7 +840,7 @@ func sampleFrameSize2(ctx context.Context, cam camera.Camera, logger logging.Log case <-ctx.Done(): return 0, 0, ctx.Err() default: - namedImage, err := camerautils2.GetStreamableNamedImageFromCamera(ctx, cam) + namedImage, err := camerautils.GetStreamableNamedImageFromCamera(ctx, cam) if err != nil { logger.Debugf("failed to get streamable named image from camera: %v", err) lastErr = err diff --git a/services/datamanager/builtin/builtin_sync_test.go b/services/datamanager/builtin/builtin_sync_test.go index 82043372240..01f10b0fcf2 100644 --- a/services/datamanager/builtin/builtin_sync_test.go +++ b/services/datamanager/builtin/builtin_sync_test.go @@ -157,15 +157,7 @@ func TestSyncEnabled(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ - camera.Named("c1"): &inject.Camera{ - ImageFunc: func( - ctx context.Context, - mimeType string, - extra map[string]interface{}, - ) ([]byte, camera.ImageMetadata, error) { - return newImageBytesResp(ctx, imgPng, mimeType) - }, - }, + camera.Named("c1"): newMockCameraWithImages(t, imgPng), }) config, deps := setupConfig(t, r, enabledBinaryCollectorConfigPath) @@ -366,15 +358,7 @@ func TestDataCaptureUploadIntegration(t *testing.T) { config, deps = setupConfig(t, r, enabledTabularCollectorConfigPath) } else { r := setupRobot(tc.cloudConnectionErr, map[resource.Name]resource.Resource{ - camera.Named("c1"): &inject.Camera{ - ImageFunc: func( - ctx context.Context, - mimeType string, - extra map[string]interface{}, - ) ([]byte, camera.ImageMetadata, error) { - return newImageBytesResp(ctx, imgPng, mimeType) - }, - }, + camera.Named("c1"): newMockCameraWithImages(t, imgPng), }) config, deps = setupConfig(t, r, enabledBinaryCollectorConfigPath) } @@ -835,15 +819,7 @@ func TestStreamingDCUpload(t *testing.T) { // Set up data manager. imgPng := newImgPng(t) r := setupRobot(nil, map[resource.Name]resource.Resource{ - camera.Named("c1"): &inject.Camera{ - ImageFunc: func( - ctx context.Context, - mimeType string, - extra map[string]interface{}, - ) ([]byte, camera.ImageMetadata, error) { - return newImageBytesResp(ctx, imgPng, mimeType) - }, - }, + camera.Named("c1"): newMockCameraWithImages(t, imgPng), }) config, deps := setupConfig(t, r, enabledBinaryCollectorConfigPath) c := config.ConvertedAttributes.(*Config) @@ -1076,15 +1052,7 @@ func TestSyncConfigUpdateBehavior(t *testing.T) { imgPng := newImgPng(t) r := setupRobot(nil, map[resource.Name]resource.Resource{ - camera.Named("c1"): &inject.Camera{ - ImageFunc: func( - ctx context.Context, - mimeType string, - extra map[string]interface{}, - ) ([]byte, camera.ImageMetadata, error) { - return newImageBytesResp(ctx, imgPng, mimeType) - }, - }, + camera.Named("c1"): newMockCameraWithImages(t, imgPng), }) config, deps := setupConfig(t, r, enabledBinaryCollectorConfigPath) c := config.ConvertedAttributes.(*Config) @@ -1244,6 +1212,25 @@ func newImageBytesResp(ctx context.Context, img image.Image, mimeType string) ([ return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil } +// newMockCameraWithImages creates a mock camera that implements both ImageFunc and ImagesFunc +// ImageFunc will fail the test if called, ImagesFunc returns a single JPEG image. +func newMockCameraWithImages(t *testing.T, imgPng image.Image) *inject.Camera { + return &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + filterSourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + t.Helper() + imgBytes, metadata, err := newImageBytesResp(ctx, imgPng, "image/jpeg") + test.That(t, err, test.ShouldBeNil) + namedImg, err := camera.NamedImageFromBytes(imgBytes, "", metadata.MimeType) + test.That(t, err, test.ShouldBeNil) + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil + }, + } +} + func newImgPng(t *testing.T) image.Image { img := image.NewNRGBA(image.Rect(0, 0, 4, 4)) var imgBuf bytes.Buffer diff --git a/services/datamanager/builtin/builtin_test.go b/services/datamanager/builtin/builtin_test.go index 0300bf32fa9..6673a2946de 100644 --- a/services/datamanager/builtin/builtin_test.go +++ b/services/datamanager/builtin/builtin_test.go @@ -469,16 +469,20 @@ 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{ - ImageFunc: func( + ImagesFunc: func( ctx context.Context, - mimeType string, + filterSourceNames []string, extra map[string]interface{}, - ) ([]byte, camera.ImageMetadata, error) { - outBytes, err := rimage.EncodeImage(ctx, imgPng, mimeType) + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + outBytes, err := rimage.EncodeImage(ctx, imgPng, "image/jpeg") if err != nil { - return nil, camera.ImageMetadata{}, err + return nil, resource.ResponseMetadata{}, err } - return outBytes, camera.ImageMetadata{MimeType: mimeType}, nil + namedImg, err := camera.NamedImageFromBytes(outBytes, "", "image/jpeg") + if err != nil { + return nil, resource.ResponseMetadata{}, err + } + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil }, }, }) diff --git a/services/datamanager/builtin/sync/upload_data_capture_file.go b/services/datamanager/builtin/sync/upload_data_capture_file.go index 17111016cde..0bfee53c04e 100644 --- a/services/datamanager/builtin/sync/upload_data_capture_file.go +++ b/services/datamanager/builtin/sync/upload_data_capture_file.go @@ -13,6 +13,7 @@ import ( "go.viam.com/rdk/data" "go.viam.com/rdk/logging" + "go.viam.com/rdk/utils" ) var ( @@ -151,7 +152,7 @@ func legacyUploadGetImages( } logger.Debugf("attempting to upload camera.GetImages response, index: %d", i) metadata := uploadMetadata(conn.partID, md) - metadata.FileExtension = getFileExtFromImageFormat(img.GetFormat()) + metadata.FileExtension = getFileExtFromImageMimeType(img.GetMimeType()) // TODO: This is wrong as the size describes the size of the entire GetImages response, but we are only // uploading one of the 2 images in that response here. if err := uploadSensorData(ctx, conn.client, metadata, newSensorData, size, path, logger); err != nil { @@ -373,18 +374,16 @@ func sendStreamingDCRequests( return nil } -func getFileExtFromImageFormat(t cameraPB.Format) string { - switch t { - case cameraPB.Format_FORMAT_JPEG: +func getFileExtFromImageMimeType(mimeType string) string { + switch mimeType { + case utils.MimeTypeJPEG: return data.ExtJpeg - case cameraPB.Format_FORMAT_PNG: + case utils.MimeTypePNG: return data.ExtPng - case cameraPB.Format_FORMAT_RAW_DEPTH: + case utils.MimeTypeRawDepth: return ".dep" - case cameraPB.Format_FORMAT_RAW_RGBA: + case utils.MimeTypeRawRGBA: return ".rgba" - case cameraPB.Format_FORMAT_UNSPECIFIED: - fallthrough default: return data.ExtDefault } diff --git a/services/vision/client.go b/services/vision/client.go index 3021ea2e229..cd183d70f03 100644 --- a/services/vision/client.go +++ b/services/vision/client.go @@ -303,7 +303,7 @@ func (c *client) CaptureAllFromCamera( var img image.Image if resp.Image.Image != nil { - mimeType := utils.FormatToMimeType[resp.Image.GetFormat()] + mimeType := resp.Image.GetMimeType() img, err = rimage.DecodeImage(ctx, resp.Image.Image, mimeType) if err != nil { return viscapture.VisCapture{}, err diff --git a/services/vision/collectors.go b/services/vision/collectors.go index 7951e188424..f6bf39e57cc 100644 --- a/services/vision/collectors.go +++ b/services/vision/collectors.go @@ -104,7 +104,7 @@ func newCaptureAllFromCameraCollector(resource interface{}, params data.Collecto } return data.NewBinaryCaptureResult(ts, []data.Binary{{ Payload: protoImage.Image, - MimeType: data.CameraFormatToMimeType(protoImage.Format), + MimeType: data.MimeTypeStringToMimeType(protoImage.MimeType), Annotations: data.Annotations{ BoundingBoxes: filteredBoundingBoxes, Classifications: filteredClassifications, diff --git a/services/vision/server.go b/services/vision/server.go index fe8f4df2935..b5141640eb0 100644 --- a/services/vision/server.go +++ b/services/vision/server.go @@ -288,10 +288,9 @@ func imageToProto(ctx context.Context, img image.Image, cameraName string) (*cam if err != nil { return nil, err } - format := utils.MimeTypeToFormat[mimeType] return &camerapb.Image{ Image: imgBytes, - Format: format, + MimeType: mimeType, SourceName: cameraName, }, nil } diff --git a/services/vision/vision_service_builder.go b/services/vision/vision_service_builder.go index b90fc49e431..68247cfb36e 100644 --- a/services/vision/vision_service_builder.go +++ b/services/vision/vision_service_builder.go @@ -159,10 +159,17 @@ func (vm *vizModel) DetectionsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.DecodeImageFromCamera(ctx, "", extra, cam) + namedImages, _, err := cam.Images(ctx, nil, extra) if err != nil { return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } + if len(namedImages) == 0 { + return nil, errors.Errorf("no images returned from camera %s", cameraName) + } + img, err := namedImages[0].Image(ctx) + if err != nil { + return nil, errors.Wrapf(err, "could not decode image from %s", cameraName) + } return vm.detectorFunc(ctx, img) } @@ -209,10 +216,17 @@ func (vm *vizModel) ClassificationsFromCamera( if err != nil { return nil, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.DecodeImageFromCamera(ctx, "", extra, cam) + namedImages, _, err := cam.Images(ctx, nil, extra) if err != nil { return nil, errors.Wrapf(err, "could not get image from %s", cameraName) } + if len(namedImages) == 0 { + return nil, errors.Errorf("no images returned from camera %s", cameraName) + } + img, err := namedImages[0].Image(ctx) + if err != nil { + return nil, errors.Wrapf(err, "could not decode image from %s", cameraName) + } fullClassifications, err := vm.classifierFunc(ctx, img) if err != nil { @@ -271,10 +285,17 @@ func (vm *vizModel) CaptureAllFromCamera( if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not find camera named %s", cameraName) } - img, err := camera.DecodeImageFromCamera(ctx, "", extra, cam) + namedImages, _, err := cam.Images(ctx, nil, extra) if err != nil { return viscapture.VisCapture{}, errors.Wrapf(err, "could not get image from %s", cameraName) } + if len(namedImages) == 0 { + return viscapture.VisCapture{}, errors.Errorf("no images returned from camera %s", cameraName) + } + img, err := namedImages[0].Image(ctx) + if err != nil { + return viscapture.VisCapture{}, errors.Wrapf(err, "could not decode image from %s", cameraName) + } var detections []objectdetection.Detection if opt.ReturnDetections { diff --git a/services/vision/vision_service_builder_test.go b/services/vision/vision_service_builder_test.go index c6418963a97..61481b60f5d 100644 --- a/services/vision/vision_service_builder_test.go +++ b/services/vision/vision_service_builder_test.go @@ -5,6 +5,7 @@ import ( "errors" "image" "testing" + "time" "go.viam.com/test" @@ -63,11 +64,17 @@ func TestDefaultCameraSettings(t *testing.T) { var s simpleSegmenter fakeCamera := &inject.Camera{ - ImageFunc: func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + ImagesFunc: func( + ctx context.Context, + filterSourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { sourceImg := image.NewRGBA(image.Rect(0, 0, 3, 3)) imgBytes, err := rimage.EncodeImage(ctx, sourceImg, utils.MimeTypePNG) test.That(t, err, test.ShouldBeNil) - return imgBytes, camera.ImageMetadata{MimeType: utils.MimeTypePNG}, nil + namedImg, err := camera.NamedImageFromBytes(imgBytes, "", utils.MimeTypePNG) + test.That(t, err, test.ShouldBeNil) + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil }, } diff --git a/testutils/inject/camera.go b/testutils/inject/camera.go index 39a346f99fe..97edb25f36f 100644 --- a/testutils/inject/camera.go +++ b/testutils/inject/camera.go @@ -19,7 +19,6 @@ type Camera struct { name resource.Name RTPPassthroughSource rtppassthrough.Source DoFunc func(ctx context.Context, cmd map[string]interface{}) (map[string]interface{}, error) - ImageFunc func(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) ImagesFunc func( ctx context.Context, filterSourceNames []string, @@ -53,17 +52,6 @@ func (c *Camera) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, err return nil, errors.New("NextPointCloud unimplemented") } -// Image calls the injected Image or the real version. -func (c *Camera) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { - if c.ImageFunc != nil { - return c.ImageFunc(ctx, mimeType, extra) - } - if c.Camera != nil { - return c.Camera.Image(ctx, mimeType, extra) - } - return nil, camera.ImageMetadata{}, errors.Wrap(ctx.Err(), "no Image function available") -} - // Properties calls the injected Properties or the real version. func (c *Camera) Properties(ctx context.Context) (camera.Properties, error) { if c.PropertiesFunc == nil { diff --git a/utils/mime.go b/utils/mime.go index e65f97ec7d6..7fa8dd1cbfe 100644 --- a/utils/mime.go +++ b/utils/mime.go @@ -3,8 +3,6 @@ package utils import ( "fmt" "strings" - - camerapb "go.viam.com/api/component/camera/v1" ) // Make sure that all mime types are registered in rimage/image_file.go with the appropriate @@ -64,21 +62,3 @@ func CheckLazyMIMEType(mimeType string) (string, bool) { } return mimeType, false } - -// MimeTypeToFormat maps Mymetype to Format. -var MimeTypeToFormat = map[string]camerapb.Format{ - MimeTypeJPEG: camerapb.Format_FORMAT_JPEG, - MimeTypePNG: camerapb.Format_FORMAT_PNG, - MimeTypeRawDepth: camerapb.Format_FORMAT_RAW_DEPTH, - MimeTypeRawRGBA: camerapb.Format_FORMAT_RAW_RGBA, - "": camerapb.Format_FORMAT_UNSPECIFIED, -} - -// FormatToMimeType maps Format to Mymetype. -var FormatToMimeType = map[camerapb.Format]string{ - camerapb.Format_FORMAT_JPEG: MimeTypeJPEG, - camerapb.Format_FORMAT_PNG: MimeTypePNG, - camerapb.Format_FORMAT_RAW_DEPTH: MimeTypeRawDepth, - camerapb.Format_FORMAT_RAW_RGBA: MimeTypeRawRGBA, - camerapb.Format_FORMAT_UNSPECIFIED: "", -}