Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[RSDK-9132] Add (Get)Image to the camera interface #4487

Open
wants to merge 52 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 3 commits
Commits
Show all changes
52 commits
Select commit Hold shift + click to select a range
a643d22
Init craziness
hexbabe Oct 24, 2024
41cb592
Use camera pkg scoped ReadImage in webcam
hexbabe Oct 25, 2024
f6e3d69
Merge branch 'main' into RSDK-9132
hexbabe Nov 4, 2024
d6439dd
Use agreed upon Image signature
hexbabe Nov 6, 2024
6417a56
Merge branch 'main' into RSDK-9132
hexbabe Nov 6, 2024
59c36ec
Fix tests
hexbabe Nov 6, 2024
16079fa
Delete ReadImager and fix mimetype formatting in data collector
hexbabe Nov 6, 2024
9084264
Fix up obstacle depth; Delete custom extra type;
hexbabe Nov 7, 2024
c44afa2
Update video source comment spec; Add helper to DRY up .Image calls w…
hexbabe Nov 7, 2024
11b1d7d
Fix obstacle depth mimetype (it needs it for re-encode since we can't…
hexbabe Nov 7, 2024
438d550
Add image metadata replacing mimetype return; Add back non empty stri…
hexbabe Nov 7, 2024
0d8081b
Forgot to include mimetype in test resp oops
hexbabe Nov 7, 2024
824c30f
Add width and height to ImageMetadata struct
hexbabe Nov 8, 2024
e744b68
Use GetGoImage in camera client Stream
hexbabe Nov 8, 2024
fd50881
Remove jpeg default in vision
hexbabe Nov 11, 2024
e570393
Revert detections, classifications, and capture all's image call to R…
hexbabe Nov 11, 2024
6646d78
Don't modify vision at all
hexbabe Nov 12, 2024
612e91c
Remove width and height from ImageMetadata; DRY up webcam and videoso…
hexbabe Nov 12, 2024
9029a05
Move ReadImageBytes to videosourcewrappers
hexbabe Nov 13, 2024
6ec0041
Rename GetGoImage -> ImageFromVideoSource
hexbabe Nov 13, 2024
ef1bd0e
Make lint
hexbabe Nov 13, 2024
d01159a
Move mimetype unmarshaling outside of capture func
hexbabe Nov 13, 2024
44611d5
Update components/camera/client.go
hexbabe Nov 13, 2024
146345f
Add error for empty bytes responses in server & client
hexbabe Nov 14, 2024
c698e16
Add empty image bytes tests
hexbabe Nov 14, 2024
9da582f
Fix random things that I am doing wrong
hexbabe Nov 14, 2024
1b51109
Revert
hexbabe Nov 14, 2024
eaf28d7
RSDK-9218: Change all of the artifacts to v4. (#4535)
dgottlieb Nov 6, 2024
4fe7e36
RSDK-8359: Update smarty to avoid unnecessary data races. (#4534)
dgottlieb Nov 6, 2024
b4e1960
RSDK-8819: Implement FTDC file rotation. (#4510)
dgottlieb Nov 6, 2024
fc6665d
APP-6785: Remove local control page - remove web workflows (#4523)
ethanlookpotts Nov 7, 2024
8afb714
APP-6850 update android build for go 1.23 (#4539)
abe-winter Nov 8, 2024
375a35f
RSDK-8611: Have test make a tls config copy to avoid concurrent acces…
dgottlieb Nov 8, 2024
5bf744c
RSDK-8837: Remove the short timeout for testing reconnects that are e…
dgottlieb Nov 8, 2024
2a1cd8b
make errors reported during discovery (#4546)
erh Nov 9, 2024
1233170
Update gripper.go (#4540)
npentrel Nov 11, 2024
95f3f42
RSDK-9090 clarify package cleanup (#4542)
maximpertsov Nov 11, 2024
b208d2c
RSDK-9240: Remove github action code coverage stuff we do not use. (#…
dgottlieb Nov 11, 2024
0b85975
[Data-3312] add basic data capture support for capturing tabular data…
nicksanford Nov 11, 2024
c44454b
RSDK-9136: issues when stopping motor with controls (#4550)
martha-johnston Nov 12, 2024
d848d20
RSDK-9037: Add AttachDirectionalAwareness to DoCommand (#4552)
martha-johnston Nov 13, 2024
09e295c
RSDK-8767 - populate local_name and remote_path to all resource names…
Kschappacher Nov 13, 2024
3edf860
APP-6696 include `os_version` tag on GOOS=darwin (#4536)
abe-winter Nov 13, 2024
b7c4635
RSDK-8926: Rover canary motor test fail because failure to set pins (…
martha-johnston Nov 14, 2024
63b7681
[DATA-3338] - collector test improvements (#4551)
nicksanford Nov 14, 2024
c91b68d
Merge branch 'main' into RSDK-9132
hexbabe Nov 14, 2024
d63980e
Fix new collector tests
hexbabe Nov 14, 2024
6ffbae2
Change image.Image getter wrapper to take in a camera resource not a …
hexbabe Nov 14, 2024
65b5bad
Merge branch 'viamrobotics:main' into RSDK-9132
hexbabe Nov 14, 2024
9a9612f
If err, then bytes and metadata should be falsy
hexbabe Nov 14, 2024
ab7e736
Use imgbuf bytes directly for a robot client test rather than encode …
hexbabe Nov 14, 2024
8244dfd
Add back ReadImage/Stream tests where it makes sense
hexbabe Nov 15, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions components/camera/camera.go
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,9 @@ type VideoSource interface {
// that may have a MIME type hint dictated in the context via gostream.WithMIMETypeHint.
Stream(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error)

// GetImage returns a single image that may have a MIME type hint dictated in the context via gostream.WithMIMETypeHint.
GetImage(ctx context.Context) (image.Image, func(), error)
hexbabe marked this conversation as resolved.
Show resolved Hide resolved
randhid marked this conversation as resolved.
Show resolved Hide resolved

// NextPointCloud returns the next immediately available point cloud, not necessarily one
// a part of a sequence. In the future, there could be streaming of point clouds.
NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error)
Expand Down
8 changes: 2 additions & 6 deletions components/camera/camera_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -183,9 +183,7 @@ func TestCameraWithNoProjector(t *testing.T) {
_, got := pc.At(0, 0, 0)
test.That(t, got, test.ShouldBeTrue)

img, _, err := camera.ReadImage(
gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)),
noProj2)
Comment on lines -186 to -188
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

camera.ReadImage still exists & should still behave the same way id did right?

If so, can we please not remove the camera.ReadImage test & just add the camera.ImageFromVideoSource tests?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It is being tested all throughout the transform camera.

Also - these two tests aren't doing much, they're testing projector/ no projector functionality, which was removed, and they can eventually be removed.

Copy link
Member Author

@hexbabe hexbabe Nov 15, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added back said tests that make sense: 8244dfd

img, _, err := noProj2.GetImage(gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG)))
randhid marked this conversation as resolved.
Show resolved Hide resolved
test.That(t, err, test.ShouldBeNil)

depthImg := img.(*rimage.DepthMap)
Expand Down Expand Up @@ -234,9 +232,7 @@ func TestCameraWithProjector(t *testing.T) {
_, got := pc.At(0, 0, 0)
test.That(t, got, test.ShouldBeTrue)

img, _, err := camera.ReadImage(
gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG),
cam2)
img, _, err := cam2.GetImage(gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG))
test.That(t, err, test.ShouldBeNil)

depthImg := img.(*rimage.DepthMap)
Expand Down
4 changes: 4 additions & 0 deletions components/camera/client.go
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,10 @@ func (c *client) Stream(
return stream, nil
}

func (c *client) GetImage(ctx context.Context) (image.Image, func(), error) {
return c.Read(ctx)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could we Read and handle release so we do not need to include release func in returns? (perhaps that would make sense in the videosourcewrapper layer).
As mentioned, this would be a larger departure from Stream.Next which assuming will cause major problems.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm gonna try to get rid of release in camera components and see what happens

Copy link
Member Author

@hexbabe hexbabe Nov 4, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks like we just need to move the rimage.EncodeImage step one level in i.e. outBytes should come out of the Image call instead of being handled in the data collector or camera server/client. Currently release is called in the collector/server/client, so we should just move it into the Image implementation. Same logic, just handled more nested in our abstraction.

I guess future module writers should get used to using rimage to encode their output i.e. read from the source bytes and output a newly constructed []byte result? Does that sound okay to everyone?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks like we just need to move the rimage.EncodeImage step one level in i.e. outBytes should come out of the Image call instead of being handled in the data collector or camera server/client.

In the client, I think that makes sense to return rimage to match the python sdk functionality -- avoid unnecessary decodes if you just want bytes.

I guess future module writers should get used to using rimage to encode their output i.e. read from the source bytes and output a newly constructed []byte result? Does that sound okay to everyone?

Would this be similar to viamimage in the python sdk, i think that works pretty well.

Looks like the server is already handling release and encoding for the caller.
Are you also suggesting removing encoding step in server GetImage?

Copy link
Member Author

@hexbabe hexbabe Nov 5, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is my WIP in server.go

	switch castedCam := cam.(type) {
	case ReadImager:
		// RSDK-8663: If available, call a method that reads exactly one image. The default
		// `ReadImage` implementation will otherwise create a gostream `Stream`, call `Next` and
		// `Close` the stream. However, between `Next` and `Close`, the stream may have pulled a
		// second image from the underlying camera. This is particularly noticeable on camera
		// clients. Where a second `GetImage` request can be processed/returned over the
		// network. Just to be discarded.
		// RSDK-9132(sean yu): In addition to what Dan said above, ReadImager is important
		// for camera components that rely on the `release` functionality provided by gostream's `Read`
		// such as viamrtsp.
		// (check that this comment is 100% true before code review then delete this paranthetical statement)
		img, release, err := castedCam.Read(ctx)
		if err != nil {
			return nil, err
		}
		defer func() {
			if release != nil {
				release()
			}
		}()
	
		actualMIME, _ := utils.CheckLazyMIMEType(req.MimeType)
		resp.MimeType = actualMIME
		outBytes, err := rimage.EncodeImage(ctx, img, req.MimeType)
		if err != nil {
			return nil, err
		}
		resp.Image = outBytes
	default:
		imgBytes, mimeType, err := cam.Image(ctx, req.MimeType, ext)
		if err != nil {
			return nil, err
		}
		actualMIME, _ := utils.CheckLazyMIMEType(mimeType)
		resp.MimeType = actualMIME
		resp.Image = imgBytes
	}

So I think yes, in the default case we don't encode anymore since the return type is now bytes

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok cool I like that.

I am little confused on why we still need the ReadImager path here. Shouldnt the camera interface now always have Image defined so we can just use that?

Copy link
Member Author

@hexbabe hexbabe Nov 5, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My thinking here is since viamrtsp uses the VideoReaderFunc and Read's release functionality to keep track of pool frames in the frame allocation optimization flow, for the server.go that serves viamrtsp, we need to be able to call release()

I think we could refactor viamrtsp though to just copy out the bytes on return early and use the new .Image pathway... I'm down to remove ReadImager entirely as long as we make it a high priority to refactor viamrtsp to use .Image and []byte

Copy link
Member

@seanavery seanavery Nov 5, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I see, interesting. I think it makes sense to leave in for now for viamrtsp compatibility.

I think we could refactor viamrtsp though to just copy out the bytes on return early and use the new .Image pathway... I'm down to remove ReadImager entirely as long as we make it a high priority to refactor viamrtsp to use .Image and []byte

Yep the whole point to having a memory manager was the issue with passing in a pointer to the avframe in VideoReaderFunc return causing segfaults with the encoding in the server.

Since we are removing encoding from the server and relying on the user to handle this, we should eventually be able to use Image pathway and simplify things quite a bit : )

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

All our go cameras will need a refactor for the full fix of this interface, I do not anticipate that we will have the best version of this code and go modules after one pr. Eventually we will get rid of Stream and Next completely. The problem is those videosourcewrapper helpers are all over the place in go modules since they're exported convenience functions.

Always export code conscientiously. But we're breaking this interface anyway, so we'll deal with the following breaks.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Okay 👍 will remove ReadImager in this PR

}

randhid marked this conversation as resolved.
Show resolved Hide resolved
func (c *client) Images(ctx context.Context) ([]NamedImage, resource.ResponseMetadata, error) {
ctx, span := trace.StartSpan(ctx, "camera::client::Images")
defer span.End()
Expand Down
96 changes: 44 additions & 52 deletions components/camera/client_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -99,13 +99,11 @@ func TestClient(t *testing.T) {
ts := time.UnixMilli(12345)
return images, resource.ResponseMetadata{CapturedAt: ts}, nil
}
injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

given stream still exists & it's behavior hasn't changed, can we please just make these additive changes, rather than removing the Stream tests?

return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) {
imageReleasedMu.Lock()
imageReleased = true
imageReleasedMu.Unlock()
return imgPng, func() {}, nil
})), nil
injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
imageReleasedMu.Lock()
imageReleased = true
imageReleasedMu.Unlock()
return imgPng, func() {}, nil
}
// depth camera
injectCameraDepth := &inject.Camera{}
Expand All @@ -127,13 +125,11 @@ func TestClient(t *testing.T) {
injectCameraDepth.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) {
return projA, nil
}
injectCameraDepth.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) {
imageReleasedMu.Lock()
imageReleased = true
imageReleasedMu.Unlock()
return depthImg, func() {}, nil
})), nil
injectCameraDepth.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
imageReleasedMu.Lock()
imageReleased = true
imageReleasedMu.Unlock()
return depthImg, func() {}, nil
}
// bad camera
injectCamera2 := &inject.Camera{}
Expand All @@ -146,8 +142,8 @@ func TestClient(t *testing.T) {
injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) {
return nil, errCameraProjectorFailed
}
injectCamera2.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
return nil, errStreamFailed
injectCamera2.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
return nil, func() {}, errGetImageFailed
}

resources := map[resource.Name]camera.Camera{
Expand Down Expand Up @@ -181,7 +177,7 @@ func TestClient(t *testing.T) {
camera1Client, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger)
test.That(t, err, test.ShouldBeNil)
ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypeRawRGBA)
frame, _, err := camera.ReadImage(ctx, camera1Client)
frame, _, err := camera1Client.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)
compVal, _, err := rimage.CompareImages(img, frame)
test.That(t, err, test.ShouldBeNil)
Expand Down Expand Up @@ -232,7 +228,7 @@ func TestClient(t *testing.T) {

ctx := gostream.WithMIMETypeHint(
context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG))
frame, _, err := camera.ReadImage(ctx, client)
frame, _, err := client.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)
dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame)
test.That(t, err, test.ShouldBeNil)
Expand All @@ -251,9 +247,9 @@ func TestClient(t *testing.T) {
client2, err := resourceAPI.RPCClient(context.Background(), conn, "", camera.Named(failCameraName), logger)
test.That(t, err, test.ShouldBeNil)

_, _, err = camera.ReadImage(context.Background(), client2)
_, _, err = client2.GetImage(context.Background())
test.That(t, err, test.ShouldNotBeNil)
test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error())
test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error())
nicksanford marked this conversation as resolved.
Show resolved Hide resolved

_, err = client2.NextPointCloud(context.Background())
test.That(t, err, test.ShouldNotBeNil)
Expand All @@ -272,63 +268,63 @@ func TestClient(t *testing.T) {
camClient, err := camera.NewClientFromConn(context.Background(), conn, "", camera.Named(testCameraName), logger)
test.That(t, err, test.ShouldBeNil)

injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
extra, ok := camera.FromContext(ctx)
test.That(t, ok, test.ShouldBeTrue)
test.That(t, extra, test.ShouldBeEmpty)
return nil, errStreamFailed
return nil, func() {}, errGetImageFailed
}

ctx := context.Background()
_, _, err = camera.ReadImage(ctx, camClient)
_, _, err = camClient.GetImage(ctx)
test.That(t, err, test.ShouldNotBeNil)
test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error())
test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error())
nicksanford marked this conversation as resolved.
Show resolved Hide resolved

injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
extra, ok := camera.FromContext(ctx)
test.That(t, ok, test.ShouldBeTrue)
test.That(t, len(extra), test.ShouldEqual, 1)
test.That(t, extra["hello"], test.ShouldEqual, "world")
return nil, errStreamFailed
return nil, func() {}, errGetImageFailed
}

// one kvp created with camera.Extra
ext := camera.Extra{"hello": "world"}
ctx = camera.NewContext(ctx, ext)
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Leaving this test deleted since we no longer have this helper function

_, _, err = camera.ReadImage(ctx, camClient)
_, _, err = camClient.GetImage(ctx)
test.That(t, err, test.ShouldNotBeNil)
test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error())
test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error())
nicksanford marked this conversation as resolved.
Show resolved Hide resolved

injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
extra, ok := camera.FromContext(ctx)
test.That(t, ok, test.ShouldBeTrue)
test.That(t, len(extra), test.ShouldEqual, 1)
test.That(t, extra[data.FromDMString], test.ShouldBeTrue)

return nil, errStreamFailed
return nil, func() {}, errGetImageFailed
}

// one kvp created with data.FromDMContextKey
ctx = context.WithValue(context.Background(), data.FromDMContextKey{}, true)
_, _, err = camera.ReadImage(ctx, camClient)
_, _, err = camClient.GetImage(ctx)
test.That(t, err, test.ShouldNotBeNil)
test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error())
test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error())

injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
extra, ok := camera.FromContext(ctx)
test.That(t, ok, test.ShouldBeTrue)
test.That(t, len(extra), test.ShouldEqual, 2)
test.That(t, extra["hello"], test.ShouldEqual, "world")
test.That(t, extra[data.FromDMString], test.ShouldBeTrue)
return nil, errStreamFailed
return nil, func() {}, errGetImageFailed
}

// merge values from data and camera
ext = camera.Extra{"hello": "world"}
ctx = camera.NewContext(ctx, ext)
_, _, err = camera.ReadImage(ctx, camClient)
_, _, err = camClient.GetImage(ctx)
test.That(t, err, test.ShouldNotBeNil)
test.That(t, err.Error(), test.ShouldContainSubstring, errStreamFailed.Error())
test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error())

test.That(t, conn.Close(), test.ShouldBeNil)
})
Expand Down Expand Up @@ -453,16 +449,14 @@ func TestClientLazyImage(t *testing.T) {
imgPng, err := png.Decode(bytes.NewReader(imgBuf.Bytes()))
test.That(t, err, test.ShouldBeNil)

injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) {
mimeType, _ := rutils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, rutils.MimeTypeRawRGBA))
switch mimeType {
case rutils.MimeTypePNG:
return imgPng, func() {}, nil
default:
return nil, nil, errInvalidMimeType
}
})), nil
injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
mimeType, _ := rutils.CheckLazyMIMEType(gostream.MIMETypeHint(ctx, rutils.MimeTypeRawRGBA))
switch mimeType {
case rutils.MimeTypePNG:
return imgPng, func() {}, nil
default:
return nil, nil, errInvalidMimeType
}
}

resources := map[resource.Name]camera.Camera{
Expand All @@ -484,15 +478,15 @@ func TestClientLazyImage(t *testing.T) {
test.That(t, err, test.ShouldBeNil)

ctx := gostream.WithMIMETypeHint(context.Background(), rutils.MimeTypePNG)
frame, _, err := camera.ReadImage(ctx, camera1Client)
frame, _, err := camera1Client.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)
// Should always lazily decode
test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{})
frameLazy := frame.(*rimage.LazyEncodedImage)
test.That(t, frameLazy.RawData(), test.ShouldResemble, imgBuf.Bytes())

ctx = gostream.WithMIMETypeHint(context.Background(), rutils.WithLazyMIMEType(rutils.MimeTypePNG))
frame, _, err = camera.ReadImage(ctx, camera1Client)
frame, _, err = camera1Client.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)
test.That(t, frame, test.ShouldHaveSameTypeAs, &rimage.LazyEncodedImage{})
frameLazy = frame.(*rimage.LazyEncodedImage)
Expand Down Expand Up @@ -582,10 +576,8 @@ func TestClientStreamAfterClose(t *testing.T) {
injectCamera.PropertiesFunc = func(ctx context.Context) (camera.Properties, error) {
return camera.Properties{}, nil
}
injectCamera.StreamFunc = func(ctx context.Context, errHandlers ...gostream.ErrorHandler) (gostream.VideoStream, error) {
return gostream.NewEmbeddedVideoStreamFromReader(gostream.VideoReaderFunc(func(ctx context.Context) (image.Image, func(), error) {
return img, func() {}, nil
})), nil
injectCamera.GetImageFunc = func(ctx context.Context) (image.Image, func(), error) {
return img, func() {}, nil
}

// Register CameraService API in our gRPC server.
Expand Down
2 changes: 1 addition & 1 deletion components/camera/collector.go
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ func newReadImageCollector(resource interface{}, params data.CollectorParams) (d

ctx = context.WithValue(ctx, data.FromDMContextKey{}, true)

img, release, err := ReadImage(ctx, camera)
img, release, err := camera.GetImage(ctx)
if err != nil {
// A modular filter component can be created to filter the readings from a component. The error ErrNoCaptureToStore
// is used in the datamanager to exclude readings from being captured and stored.
Expand Down
4 changes: 1 addition & 3 deletions components/camera/fake/camera_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -93,9 +93,7 @@ func TestRTPPassthrough(t *testing.T) {
camera, err := NewCamera(context.Background(), nil, cfg, logger)
test.That(t, err, test.ShouldBeNil)

stream, err := camera.Stream(context.Background())
test.That(t, err, test.ShouldBeNil)
img, _, err := stream.Next(context.Background())
img, _, err := camera.GetImage(context.Background())
test.That(t, err, test.ShouldBeNil)
// GetImage returns the world jpeg
test.That(t, img.Bounds(), test.ShouldResemble, image.Rectangle{Max: image.Point{X: 480, Y: 270}})
Expand Down
18 changes: 3 additions & 15 deletions components/camera/fake/image_file_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,6 @@ func TestPCD(t *testing.T) {
cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger)
test.That(t, err, test.ShouldBeNil)

_, err = cam.Stream(ctx)
test.That(t, err, test.ShouldBeNil)

pc, err := cam.NextPointCloud(ctx)
test.That(t, err, test.ShouldBeNil)
test.That(t, pc.Size(), test.ShouldEqual, 628)
Expand All @@ -45,13 +42,10 @@ func TestPCD(t *testing.T) {
cam, err = newCamera(ctx, resource.Name{API: camera.API}, cfg, logger)
test.That(t, err, test.ShouldBeNil)

stream, err := cam.Stream(ctx)
test.That(t, err, test.ShouldBeNil)

readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg"))
test.That(t, err, test.ShouldBeNil)

strmImg, _, err := stream.Next(ctx)
strmImg, _, err := cam.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)
test.That(t, strmImg, test.ShouldResemble, readInImage)
test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds())
Expand All @@ -68,16 +62,13 @@ func TestColor(t *testing.T) {
cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger)
test.That(t, err, test.ShouldBeNil)

stream, err := cam.Stream(ctx)
test.That(t, err, test.ShouldBeNil)

_, err = cam.NextPointCloud(ctx)
test.That(t, err, test.ShouldNotBeNil)

readInImage, err := rimage.NewImageFromFile(artifact.MustPath("vision/objectdetection/detection_test.jpg"))
test.That(t, err, test.ShouldBeNil)

strmImg, _, err := stream.Next(ctx)
strmImg, _, err := cam.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)
test.That(t, strmImg, test.ShouldResemble, readInImage)
test.That(t, strmImg.Bounds(), test.ShouldResemble, readInImage.Bounds())
Expand Down Expand Up @@ -108,13 +99,10 @@ func TestColorOddResolution(t *testing.T) {
cam, err := newCamera(ctx, resource.Name{API: camera.API}, cfg, logger)
test.That(t, err, test.ShouldBeNil)

stream, err := cam.Stream(ctx)
test.That(t, err, test.ShouldBeNil)

readInImage, err := rimage.NewImageFromFile(imgFilePath)
test.That(t, err, test.ShouldBeNil)

strmImg, _, err := stream.Next(ctx)
strmImg, _, err := cam.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)

expectedBounds := image.Rect(0, 0, readInImage.Bounds().Dx()-1, readInImage.Bounds().Dy()-1)
Expand Down
5 changes: 1 addition & 4 deletions components/camera/ffmpeg/ffmpeg_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,10 @@ func TestFFMPEGCamera(t *testing.T) {
path := artifact.MustPath("components/camera/ffmpeg/testsrc.mpg")
cam, err := NewFFMPEGCamera(ctx, &Config{VideoPath: path}, logger)
test.That(t, err, test.ShouldBeNil)
stream, err := cam.Stream(ctx)
test.That(t, err, test.ShouldBeNil)
for i := 0; i < 5; i++ {
_, _, err := stream.Next(ctx)
_, _, err := cam.GetImage(ctx)
test.That(t, err, test.ShouldBeNil)
}
test.That(t, stream.Close(context.Background()), test.ShouldBeNil)
test.That(t, cam.Close(context.Background()), test.ShouldBeNil)
}

Expand Down
14 changes: 14 additions & 0 deletions components/camera/replaypcd/replaypcd.go
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ package replaypcd
import (
"bytes"
"context"
"image"
"net/http"
"sync"
"time"
Expand Down Expand Up @@ -346,6 +347,19 @@ func (replay *pcdCamera) Stream(ctx context.Context, errHandlers ...gostream.Err
return stream, errors.New("Stream is unimplemented")
}

func (replay *pcdCamera) GetImage(ctx context.Context) (image.Image, func(), error) {
stream, err := replay.Stream(ctx)
if err != nil {
return nil, func() {}, err
}
defer func() {
if err := stream.Close(ctx); err != nil {
replay.logger.Errorf("stream failed to close: %w", err)
}
}()
return stream.Next(ctx)
}

randhid marked this conversation as resolved.
Show resolved Hide resolved
// Close stops replay camera, closes the channels and its connections to the cloud.
func (replay *pcdCamera) Close(ctx context.Context) error {
replay.mu.Lock()
Expand Down
5 changes: 0 additions & 5 deletions components/camera/replaypcd/replaypcd_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -660,11 +660,6 @@ func TestReplayPCDUnimplementedFunctions(t *testing.T) {
replayCamera, _, serverClose, err := createNewReplayPCDCamera(ctx, t, replayCamCfg, true)
test.That(t, err, test.ShouldBeNil)

t.Run("Stream", func(t *testing.T) {
_, err := replayCamera.Stream(ctx, nil)
test.That(t, err.Error(), test.ShouldEqual, "Stream is unimplemented")
})

err = replayCamera.Close(ctx)
test.That(t, err, test.ShouldBeNil)

Expand Down
2 changes: 1 addition & 1 deletion components/camera/server.go
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ func (s *serviceServer) GetImage(
// network. Just to be discarded.
img, release, err = castedCam.Read(ctx)
default:
img, release, err = ReadImage(gostream.WithMIMETypeHint(ctx, req.MimeType), cam)
img, release, err = cam.GetImage(gostream.WithMIMETypeHint(ctx, req.MimeType))
hexbabe marked this conversation as resolved.
Show resolved Hide resolved
hexbabe marked this conversation as resolved.
Show resolved Hide resolved
}
if err != nil {
return nil, err
Expand Down
Loading
Loading