Skip to content
Draft
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
Prev Previous commit
Remove GetImages streaming feature flag and make it the default; Upda…
…te tests; Make lint
  • Loading branch information
hexbabe committed Oct 13, 2025
commit 4ffab13480c64dfa6b1524dfbbd97a2c976c0397
1 change: 0 additions & 1 deletion components/camera/camera.go
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,6 @@ type Camera interface {
Properties(ctx context.Context) (Properties, error)
}


// 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 {
Expand Down
21 changes: 0 additions & 21 deletions components/camera/camera_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -262,27 +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)
}


// TestImages asserts the core expected behavior of the Images API.
func TestImages(t *testing.T) {
ctx := context.Background()
Expand Down
8 changes: 6 additions & 2 deletions components/camera/client_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,11 @@ func TestClient(t *testing.T) {
injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) {
return nil, errCameraProjectorFailed
}
injectCamera2.ImagesFunc = func(ctx context.Context, filterSourceNames []string, extra map[string]interface{}) ([]camera.NamedImage, resource.ResponseMetadata, error) {
injectCamera2.ImagesFunc = func(
ctx context.Context,
filterSourceNames []string,
extra map[string]interface{},
) ([]camera.NamedImage, resource.ResponseMetadata, error) {
return nil, resource.ResponseMetadata{}, errGetImageFailed
}

Expand Down Expand Up @@ -196,7 +200,7 @@ func TestClient(t *testing.T) {
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

Expand Down
6 changes: 5 additions & 1 deletion components/camera/collectors_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,11 @@ func newCamera(
pcd pointcloud.PointCloud,
) camera.Camera {
v := &inject.Camera{}
v.ImagesFunc = func(ctx context.Context, filterSourceNames []string, extra map[string]interface{}) ([]camera.NamedImage, resource.ResponseMetadata, 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, resource.ResponseMetadata{}, err
Expand Down
14 changes: 4 additions & 10 deletions components/camera/server.go
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@ package camera
import (
"context"
"fmt"
"sync"

"github.com/pkg/errors"
"go.opencensus.io/trace"
Expand All @@ -21,22 +20,17 @@ 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,
coll: coll,
logger: logger,
}
}

Expand Down
8 changes: 5 additions & 3 deletions components/camera/server_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -26,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")
Expand Down Expand Up @@ -168,7 +167,11 @@ func TestServer(t *testing.T) {
injectCamera2.ProjectorFunc = func(ctx context.Context) (transform.Projector, error) {
return nil, errCameraProjectorFailed
}
injectCamera2.ImagesFunc = func(ctx context.Context, filterSourceNames []string, extra map[string]interface{}) ([]camera.NamedImage, resource.ResponseMetadata, error) {
injectCamera2.ImagesFunc = func(
ctx context.Context,
filterSourceNames []string,
extra map[string]interface{},
) ([]camera.NamedImage, resource.ResponseMetadata, error) {
return nil, resource.ResponseMetadata{}, errGetImageFailed
}

Expand Down Expand Up @@ -413,4 +416,3 @@ func TestServer(t *testing.T) {
test.That(t, err.Error(), test.ShouldContainSubstring, errGetImageFailed.Error())
})
}

16 changes: 12 additions & 4 deletions components/camera/transformpipeline/pipeline_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@ package transformpipeline

import (
"context"
"errors"
"testing"

"github.com/pion/mediadevices/pkg/prop"
Expand Down Expand Up @@ -213,14 +212,23 @@ func TestTransformPipelineValidateFail(t *testing.T) {

func TestVideoSourceFromCameraError(t *testing.T) {
malformedCam := &inject.Camera{
ImagesFunc: func(ctx context.Context, filterSourceNames []string, extra map[string]interface{}) ([]camera.NamedImage, resource.ResponseMetadata, error) {
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)
}
1 change: 0 additions & 1 deletion components/camera/videosource/webcam.go
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,6 @@ func (c *webcam) ensureActive() error {
return nil
}


func (c *webcam) NextPointCloud(ctx context.Context) (pointcloud.PointCloud, error) {
c.mu.RLock()
defer c.mu.RUnlock()
Expand Down
6 changes: 5 additions & 1 deletion robot/client/client_test.go
Original file line number Diff line number Diff line change
Expand Up @@ -347,7 +347,11 @@ func TestStatusClient(t *testing.T) {
var imgBuf bytes.Buffer
test.That(t, png.Encode(&imgBuf, img), test.ShouldBeNil)

injectCamera.ImagesFunc = func(ctx context.Context, filterSourceNames []string, extra map[string]interface{}) ([]camera.NamedImage, resource.ResponseMetadata, error) {
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
Expand Down
135 changes: 121 additions & 14 deletions robot/web/stream/camera/camera.go
Original file line number Diff line number Diff line change
Expand Up @@ -10,51 +10,158 @@ 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
}
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) {
namedImages, _, err := cam.Images(ctx, nil, nil)
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
}
if len(namedImages) == 0 {
return nil, func() {}, fmt.Errorf("no images returned from camera")
}
img, err := namedImages[0].Image(ctx)

img, err = cropToEvenDimensions(img)
if err != nil {
sourceName = nil
return nil, func() {}, err
}

return img, func() {}, nil
})

namedImages, _, err := cam.Images(ctx, nil, 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
}
if len(namedImages) == 0 {
return gostream.NewVideoSource(reader, prop.Video{}), nil
}
img, err := namedImages[0].Image(ctx)
if err != nil {
return gostream.NewVideoSource(reader, prop.Video{}), nil //nolint:nilerr
}

return gostream.NewVideoSource(reader, prop.Video{Width: img.Bounds().Dx(), Height: img.Bounds().Dy()}), nil
}
Loading
Loading