diff --git a/cli/app.go b/cli/app.go index d2eb237674a..d7f93221342 100644 --- a/cli/app.go +++ b/cli/app.go @@ -87,7 +87,6 @@ const ( moduleFlagVisibility = "visibility" moduleFlagResourceType = "resource-type" moduleFlagModelName = "model-name" - moduleFlagEnableCloud = "enable-cloud" moduleFlagRegister = "register" moduleFlagDryRun = "dry-run" moduleFlagUpload = "upload" @@ -100,7 +99,6 @@ const ( moduleBuildFlagGroupLogs = "group-logs" moduleBuildRestartOnly = "restart-only" moduleBuildFlagNoBuild = "no-build" - moduleBuildFlagCloudBuild = "cloud-build" moduleBuildFlagCloudConfig = "cloud-config" moduleBuildFlagID = "build-id" moduleBuildFlagOAuthLink = "oauth-link" @@ -469,6 +467,49 @@ var app = &cli.App{ }, }, Commands: []*cli.Command{ + { + Name: "defaults", + Usage: "Set or clear default argument values", + UsageText: createUsageText("defaults", nil, false, false), + Subcommands: []*cli.Command{ + { + Name: "set-org", + Usage: "Set default organization argument", + Flags: []cli.Flag{ + &AliasStringFlag{ + cli.StringFlag{ + Name: generalFlagOrgID, // some functions require an ID, so we should do the same for defaults + Required: true, + }, + }, + }, + Action: createCommandWithT(defaultsSetOrgAction), + }, + { + Name: "clear-org", + Usage: "Clear default organization argument", + Action: createCommandWithT(defaultsClearOrgAction), + }, + { + Name: "set-location", + Usage: "Set default location argument", + Flags: []cli.Flag{ + &AliasStringFlag{ + cli.StringFlag{ + Name: generalFlagLocationID, // some functions require an ID, so we should do the same for defaults + Required: true, + }, + }, + }, + Action: createCommandWithT(defaultsSetLocationAction), + }, + { + Name: "clear-location", + Usage: "Clear default location argument", + Action: createCommandWithT(defaultsClearLocationAction), + }, + }, + }, { Name: "traces", Usage: "Work with viam-server traces", @@ -1001,9 +1042,9 @@ Note: There is no progress meter while copying is in progress. UsageText: createUsageText("organizations api-key create", []string{generalFlagOrgID}, true, false), Flags: []cli.Flag{ &cli.StringFlag{ - Name: generalFlagOrgID, - Required: true, - Usage: "the org to create an api key for", + Name: generalFlagOrgID, + Usage: "the org to create an api key for", + DefaultText: "the default org set with `viam defaults set-org`", }, &cli.StringFlag{ Name: generalFlagName, @@ -1034,7 +1075,7 @@ Note: There is no progress meter while copying is in progress. cli.StringFlag{ Name: generalFlagOrganization, Aliases: []string{generalFlagAliasOrg, generalFlagOrgID, generalFlagAliasOrgName}, - DefaultText: "first organization alphabetically", + DefaultText: "the org set by `viam defaults set-org` if it exists, else the first one alphabetically", }, }, }, @@ -1051,9 +1092,9 @@ Note: There is no progress meter while copying is in progress. UsageText: createUsageText("locations api-key create", []string{generalFlagLocationID}, true, false), Flags: []cli.Flag{ &cli.StringFlag{ - Name: generalFlagLocationID, - Required: true, - Usage: "id of the location to create an api-key for", + Name: generalFlagLocationID, + Usage: "id of the location to create an api-key for", + DefaultText: "the default location set with `viam defaults set-location`", }, &cli.StringFlag{ Name: generalFlagName, @@ -2318,14 +2359,14 @@ Note: There is no progress meter while copying is in progress. cli.StringFlag{ Name: generalFlagOrganization, Aliases: []string{generalFlagAliasOrg, generalFlagOrgID, generalFlagAliasOrgName}, - DefaultText: "first organization alphabetically", + DefaultText: "the default org argument if set, else the first organization alphabetically", }, }, &AliasStringFlag{ cli.StringFlag{ Name: generalFlagLocation, Aliases: []string{generalFlagLocationID, generalFlagAliasLocationName}, - DefaultText: "first location alphabetically", + DefaultText: "the default location argument if set, else the first location alphabetically", }, }, &cli.BoolFlag{ @@ -2950,10 +2991,6 @@ After creation, use 'viam module update' to push your new module to app.viam.com Usage: "name for the particular resource subtype implementation." + " for example, a sensor model that detects moisture might be named 'moisture'", }, - &cli.BoolFlag{ - Name: moduleFlagEnableCloud, - Usage: "generate Github workflows to build module", - }, &cli.BoolFlag{ Name: moduleFlagRegister, Usage: "register module with Viam to associate with your organization", @@ -3010,10 +3047,6 @@ viam module upload --version "0.1.0" --platform "linux/amd64" --upload "./bin/my Example uploading a whole directory: viam module upload --version "0.1.0" --platform "linux/amd64" --upload "./bin" (this example requires the entrypoint in the meta.json to be inside the bin directory like "./bin/[your path here]") - -Example uploading a custom tarball of your module: -tar -czf packaged-module.tar.gz ./src requirements.txt run.sh -viam module upload --version "0.1.0" --platform "linux/amd64" --upload "packaged-module.tar.gz" `, UsageText: createUsageText("module upload", []string{generalFlagVersion, moduleFlagPlatform, moduleFlagUpload}, true, false), Flags: []cli.Flag{ diff --git a/cli/auth.go b/cli/auth.go index b9fc5fe0b07..b2a6626ec76 100644 --- a/cli/auth.go +++ b/cli/auth.go @@ -313,7 +313,13 @@ func OrganizationsAPIKeyCreateAction(cCtx *cli.Context, args organizationsAPIKey } func (c *viamClient) organizationsAPIKeyCreateAction(cCtx *cli.Context, args organizationsAPIKeyCreateArgs) error { + var err error orgID := args.OrgID + if orgID == "" { + if orgID, err = getDefaultOrg(cCtx); err != nil { + return errors.New("must specify an org ID to create an API key for") + } + } keyName := args.Name if keyName == "" { keyName = c.generateDefaultKeyName() @@ -367,6 +373,10 @@ func LocationAPIKeyCreateAction(cCtx *cli.Context, args locationAPIKeyCreateArgs func (c *viamClient) locationAPIKeyCreateAction(cCtx *cli.Context, args locationAPIKeyCreateArgs) error { locationID := args.LocationID + if locationID == "" { + //nolint:errcheck // if there's an error we just fallback to the old logic + locationID, _ = getDefaultLocation(cCtx) + } orgID := args.OrgID keyName := args.Name @@ -480,6 +490,11 @@ func (c *viamClient) ensureLoggedInInner() error { return nil } + globalArgs, err := getGlobalArgs(c.c) + if err != nil { + return err + } + if c.conf.Auth == nil { return errors.New("not logged in: run the following command to login:\n\tviam login") } @@ -494,10 +509,7 @@ func (c *viamClient) ensureLoggedInInner() error { // expired. newToken, err := c.authFlow.refreshToken(c.c.Context, authToken) if err != nil { - debugFlag := false - if globalArgs, err := getGlobalArgs(c.c); err == nil { - debugFlag = globalArgs.Debug - } + debugFlag := globalArgs.Debug debugf(c.c.App.Writer, debugFlag, "Token refresh error: %v", err) utils.UncheckedError(c.logout()) // clear cache if failed to refresh return errors.New("error while refreshing token, logging out. Please log in again") @@ -534,6 +546,23 @@ func (c *viamClient) ensureLoggedInInner() error { c.mlInferenceClient = mlinferencepb.NewMLInferenceServiceClient(conn) c.buildClient = buildpb.NewBuildServiceClient(conn) + // if there's no default org and we're in a profile, there should only be the one org + // so we can automatically set that as the default + if c.conf.DefaultOrg == "" { + whichProfile, _ := whichProfile(globalArgs) + if !globalArgs.DisableProfiles && whichProfile != nil { + orgs, err := c.listOrganizations() + if err != nil && !globalArgs.Quiet { + warningf(c.c.App.ErrWriter, "no default org set for profile and unable to infer one") + // this should always be true for now, but might change if/when user level API keys exist + } else if len(orgs) == 1 { + if err = c.writeDefaultOrg(c.c, c.conf, orgs[0].Id); err != nil && !globalArgs.Quiet { + warningf(c.c.App.ErrWriter, "unable to set default org for profile %s", *whichProfile) + } + } + } + } + return nil } diff --git a/cli/auth_test.go b/cli/auth_test.go index 57a9cc516d9..e8c74eb4a58 100644 --- a/cli/auth_test.go +++ b/cli/auth_test.go @@ -53,7 +53,7 @@ func TestAPIKeyCreateAction(t *testing.T) { asc := &inject.AppServiceClient{ CreateKeyFunc: createKeyFunc, } - cCtx, ac, out, errOut := setup(asc, nil, nil, nil, "token") + cCtx, ac, out, errOut := setup(asc, nil, nil, map[string]any{"org-id": "my-org"}, "token") test.That(t, ac.organizationsAPIKeyCreateAction(cCtx, parseStructFromCtx[organizationsAPIKeyCreateArgs](cCtx)), test.ShouldBeNil) test.That(t, len(errOut.messages), test.ShouldEqual, 0) diff --git a/cli/client.go b/cli/client.go index e23c6c3b139..be3a8efed41 100644 --- a/cli/client.go +++ b/cli/client.go @@ -605,7 +605,11 @@ func ListLocationsAction(c *cli.Context, args listLocationsArgs) error { if orgStr == "" { orgStr = c.Args().First() } - if orgStr == "" { + if orgStr == "" { // first, see if we have a default set + //nolint:errcheck // if there's an error then we'll just fall back to the old logic + orgStr, _ = getDefaultOrg(c) + } + if orgStr == "" { // if there's still not an orgStr, then we can fall back to the alphabetically first orgs, err := client.listOrganizations() if err != nil { return errors.Wrap(err, "could not list organizations") @@ -951,6 +955,14 @@ func ListRobotsAction(c *cli.Context, args listRobotsActionArgs) error { } orgStr := args.Organization locStr := args.Location + if orgStr == "" { + //nolint:errcheck // if there's an error we fallback to old logic + orgStr, _ = getDefaultOrg(c) + } + if locStr == "" { + //nolint:errcheck // if there's an error we fallback to old logic + locStr, _ = getDefaultLocation(c) + } if args.All { return client.listAllRobotsInOrg(c, orgStr) } diff --git a/cli/config.go b/cli/config.go index c3936c074d3..875f437f58a 100644 --- a/cli/config.go +++ b/cli/config.go @@ -134,6 +134,8 @@ type Config struct { LastUpdateCheck string `json:"last_update_check"` LatestVersion string `json:"latest_version"` profile string + DefaultOrg string `json:"default_org"` + DefaultLocation string `json:"default_location"` } func (conf *Config) tryUnmarshallWithToken(configBytes []byte) error { diff --git a/cli/defaults.go b/cli/defaults.go new file mode 100644 index 00000000000..c71f28315f3 --- /dev/null +++ b/cli/defaults.go @@ -0,0 +1,190 @@ +package cli + +import ( + "fmt" + + "github.com/urfave/cli/v2" + apppb "go.viam.com/api/app/v1" +) + +type defaultsSetOrgArgs struct { + OrgID string +} + +func getDefaultOrg(cCtx *cli.Context) (string, error) { + config, err := ConfigFromCache(cCtx) + if err != nil { + return "", err + } + + return config.DefaultOrg, nil +} + +func getDefaultLocation(cCtx *cli.Context) (string, error) { + config, err := ConfigFromCache(cCtx) + if err != nil { + return "", err + } + + return config.DefaultLocation, nil +} + +// verifies that a passed org exists and is accessible, then sets it as the default within the config +func (c *viamClient) setDefaultOrg(cCtx *cli.Context, config *Config, orgStr string) (*Config, error) { + // we're setting a new default org, so try to verify that it actually exists and there's + // permission to access it + if orgStr != "" { + if orgs, err := c.listOrganizations(); err != nil { + warningf(cCtx.App.ErrWriter, "unable to verify existence of org %s: %v", orgStr, err) + } else { + orgFound := false + for _, org := range orgs { + if orgStr == org.Id { + orgFound = true + break + } + } + if !orgFound { + var profileWarning string + if gArgs, err := getGlobalArgs(cCtx); err == nil { + currProfile, _ := whichProfile(gArgs) + if currProfile != nil && *currProfile != "" { + profileWarning = ". You are currently logged in with profile %s. Did you mean to add a default to top level config?" + } + } + return nil, fmt.Errorf("no org found matching ID %s%s", orgStr, profileWarning) + } + } + } + + config.DefaultOrg = orgStr + return config, nil +} + +func (c *viamClient) writeDefaultOrg(cCtx *cli.Context, config *Config, orgStr string) error { + config, err := c.setDefaultOrg(cCtx, config, orgStr) + if err != nil { + return err + } + + return storeConfigToCache(config) +} + +func writeDefaultOrg(cCtx *cli.Context, orgStr string) error { + client, err := newViamClient(cCtx) + if err != nil { + return err + } + + config, err := ConfigFromCache(cCtx) + if err != nil { + return err + } + + return client.writeDefaultOrg(cCtx, config, orgStr) +} + +func (c *viamClient) setDefaultLocation(cCtx *cli.Context, config *Config, locStr string) (*Config, error) { + var err error + // we're setting a new default location arg, so verify that the location exists and is + // accessible given the current auth settings and default org argument. + if locStr != "" { + orgs := []*apppb.Organization{} + + if config.DefaultOrg == "" { + warningf(cCtx.App.ErrWriter, "attempting to set a default location argument when no default org argument is set."+ + " This can work, but may result in unexpected behavior.") + + orgs, err = c.listOrganizations() + if err != nil { + warningf(cCtx.App.ErrWriter, "unable to list organizations to find location %s: %v", locStr, err) + } + } else { + org, err := c.getOrg(config.DefaultOrg) + if err != nil { + warningf(cCtx.App.ErrWriter, "unable to lookup org with default org value %s", config.DefaultOrg) + } else { + orgs = append(orgs, org) + } + } + + locFound := false + for _, org := range orgs { + locs, err := c.listLocations(org.Id) + if err != nil { + warningf(cCtx.App.ErrWriter, "unable to list locations for org %s: %v", org.Id, err) + continue + } + for _, loc := range locs { + if locStr == loc.Id { + locFound = true + break + } + } + if locFound { + break + } + } + + if !locFound { + var profileWarning string + if gArgs, err := getGlobalArgs(cCtx); err == nil { + currProfile, _ := whichProfile(gArgs) + if currProfile != nil && *currProfile != "" { + profileWarning = ". You are currently logged in with profile %s. Did you mean to add a default to top level config?" + } + } + var forOrgWarning string + if config.DefaultOrg != "" { + forOrgWarning = fmt.Sprintf(" in default org %s", config.DefaultOrg) + } + return nil, fmt.Errorf("no location found matching ID %s%s%s", locStr, forOrgWarning, profileWarning) + } + } + + config.DefaultLocation = locStr + return config, nil +} + +func (c *viamClient) writeDefaultLocation(cCtx *cli.Context, config *Config, locationStr string) error { + config, err := c.setDefaultLocation(cCtx, config, locationStr) + if err != nil { + return err + } + + return storeConfigToCache(config) +} + +func writeDefaultLocation(cCtx *cli.Context, locationStr string) error { + client, err := newViamClient(cCtx) + if err != nil { + return err + } + + config, err := ConfigFromCache(cCtx) + if err != nil { + return err + } + + return client.writeDefaultLocation(cCtx, config, locationStr) +} + +func defaultsSetOrgAction(cCtx *cli.Context, args defaultsSetOrgArgs) error { + return writeDefaultOrg(cCtx, args.OrgID) +} + +func defaultsClearOrgAction(cCtx *cli.Context, args emptyArgs) error { + return writeDefaultOrg(cCtx, "") +} + +type defaultsSetLocationArgs struct { + LocationID string +} + +func defaultsSetLocationAction(cCtx *cli.Context, args defaultsSetLocationArgs) error { + return writeDefaultLocation(cCtx, args.LocationID) +} + +func defaultsClearLocationAction(cCtx *cli.Context, args emptyArgs) error { + return writeDefaultLocation(cCtx, "") +} diff --git a/cli/defaults_test.go b/cli/defaults_test.go new file mode 100644 index 00000000000..185e0c27ac4 --- /dev/null +++ b/cli/defaults_test.go @@ -0,0 +1,133 @@ +package cli + +import ( + "context" + "testing" + + "github.com/google/uuid" + apppb "go.viam.com/api/app/v1" + "go.viam.com/test" + "google.golang.org/grpc" + + "go.viam.com/rdk/testutils/inject" +) + +func TestSetOrg(t *testing.T) { + orgID := uuid.New().String() + organizations := []*apppb.Organization{ + { + Id: orgID, + }, + } + listOrgsFunc := func(ctx context.Context, in *apppb.ListOrganizationsRequest, + opts ...grpc.CallOption, + ) (*apppb.ListOrganizationsResponse, error) { + return &apppb.ListOrganizationsResponse{Organizations: organizations}, nil + } + + asc := &inject.AppServiceClient{ + ListOrganizationsFunc: listOrgsFunc, + } + + tests := []struct { + name string + orgID string + shouldPass bool + }{ + { + name: "matching org ID", + orgID: orgID, + shouldPass: true, + }, + { + name: "non-matching org ID", + orgID: "some-other-org-id", + shouldPass: false, + }, + { + name: "empty org-id for clearing org", + shouldPass: true, + }, + } + cCtx, vc, _, _ := setup(asc, nil, nil, map[string]any{"org-id": orgID}, "token") + for _, tt := range tests { + t.Run(tt.name, func(t *testing.T) { + config := Config{} + _, err := vc.setDefaultOrg(cCtx, &config, tt.orgID) + test.That(t, err == nil, test.ShouldEqual, tt.shouldPass) + if tt.shouldPass { + test.That(t, config.DefaultOrg, test.ShouldResemble, tt.orgID) + } + }) + } +} + +func TestSetLocation(t *testing.T) { + orgID := uuid.New().String() + organizations := []*apppb.Organization{ + { + Id: orgID, + }, + } + listOrgsFunc := func(ctx context.Context, in *apppb.ListOrganizationsRequest, + opts ...grpc.CallOption, + ) (*apppb.ListOrganizationsResponse, error) { + return &apppb.ListOrganizationsResponse{Organizations: organizations}, nil + } + locations := []*apppb.Location{ + { + Id: "my-loc-id", + }, + } + listLocationsFunc := func(ctx context.Context, in *apppb.ListLocationsRequest, + opts ...grpc.CallOption, + ) (*apppb.ListLocationsResponse, error) { + return &apppb.ListLocationsResponse{Locations: locations}, nil + } + + asc := &inject.AppServiceClient{ + ListLocationsFunc: listLocationsFunc, + ListOrganizationsFunc: listOrgsFunc, + } + + tests := []struct { + name string + locationID string + shouldPass bool + }{ + { + name: "matching location ID", + locationID: "my-loc-id", + shouldPass: true, + }, + { + name: "non-matching location ID", + locationID: "some-other-loc-id", + shouldPass: false, + }, + { + name: "empty loc-id for clearing location", + shouldPass: true, + }, + } + cCtx, vc, _, errOut := setup(asc, nil, nil, map[string]any{"location-id": "my-loc-id"}, "token") + for _, tt := range tests { + t.Run(tt.name, func(t *testing.T) { + config := Config{} + _, err := vc.setDefaultLocation(cCtx, &config, tt.locationID) + test.That(t, err == nil, test.ShouldEqual, tt.shouldPass) + if tt.shouldPass { + test.That(t, config.DefaultLocation, test.ShouldResemble, tt.locationID) + } else { + test.That(t, len(errOut.messages), test.ShouldBeGreaterThan, 0) + test.That(t, errOut.messages[0], test.ShouldEqual, "Warning: ") + test.That(t, + errOut.messages[1], + test.ShouldContainSubstring, + "attempting to set a default location argument when no default org argument is set", + ) + test.That(t, err.Error(), test.ShouldEqual, "no location found matching ID some-other-loc-id") + } + }) + } +} diff --git a/cli/module.schema.json b/cli/module.schema.json index 326c8c97ba5..7e422125ac4 100644 --- a/cli/module.schema.json +++ b/cli/module.schema.json @@ -81,7 +81,7 @@ "type": "string", "default": "make module.tar.gz", "description": "Shell command to build your module's tarball", - "examples": ["make module.tar.gz", "./run.sh"] + "examples": ["make module.tar.gz"] }, "setup": { "type": "string", diff --git a/cli/module_build.go b/cli/module_build.go index a392a8598fc..003609719a4 100644 --- a/cli/module_build.go +++ b/cli/module_build.go @@ -553,7 +553,6 @@ type reloadModuleArgs struct { NoBuild bool Local bool NoProgress bool - CloudBuild bool // CloudConfig is a path to the `viam.json`, or the config containing the robot ID. CloudConfig string diff --git a/cli/module_generate.go b/cli/module_generate.go index c7b1deb411b..abb228f6a38 100644 --- a/cli/module_generate.go +++ b/cli/module_generate.go @@ -64,7 +64,6 @@ type generateModuleArgs struct { PublicNamespace string ResourceSubtype string ModelName string - EnableCloud bool Register bool DryRun bool } @@ -113,14 +112,13 @@ func (c *viamClient) generateModuleAction(cCtx *cli.Context, args generateModule var err error newModule = &modulegen.ModuleInputs{ - ModuleName: args.Name, - Language: args.Language, - Visibility: args.Visibility, - Namespace: args.PublicNamespace, - ResourceSubtype: args.ResourceSubtype, - ModelName: args.ModelName, - EnableCloudBuild: args.EnableCloud, - RegisterOnApp: args.Register, + ModuleName: args.Name, + Language: args.Language, + Visibility: args.Visibility, + Namespace: args.PublicNamespace, + ResourceSubtype: args.ResourceSubtype, + ModelName: args.ModelName, + RegisterOnApp: args.Register, } if err := newModule.CheckResourceAndSetType(); err != nil { @@ -345,10 +343,6 @@ func promptUser(module *modulegen.ModuleInputs) error { } return nil }), - huh.NewConfirm(). - Title("Enable cloud build"). - Description("If enabled, this will generate GitHub workflows to build your module."). - Value(&module.EnableCloudBuild), registerWidget, ), ).WithHeight(25).WithWidth(88) @@ -503,60 +497,56 @@ func renderCommonFiles(c *cli.Context, module modulegen.ModuleInputs, globalArgs } // Render workflows for cloud build - if module.EnableCloudBuild { - debugf(c.App.Writer, globalArgs.Debug, "\tCreating cloud build workflow") - destWorkflowPath := filepath.Join(module.ModuleName, ".github") - if err = os.Mkdir(destWorkflowPath, 0o750); err != nil { - return errors.Wrap(err, "failed to create cloud build workflow") - } + debugf(c.App.Writer, globalArgs.Debug, "\tCreating cloud build workflow") + destWorkflowPath := filepath.Join(module.ModuleName, ".github") + if err = os.Mkdir(destWorkflowPath, 0o750); err != nil { + return errors.Wrap(err, "failed to create cloud build workflow") + } + + workflowPath := filepath.Join(templatesPath, ".github") + workflowFS, err := fs.Sub(templates, workflowPath) + if err != nil { + return errors.Wrap(err, "failed to create cloud build workflow") + } - workflowPath := filepath.Join(templatesPath, ".github") - workflowFS, err := fs.Sub(templates, workflowPath) + err = fs.WalkDir(workflowFS, ".", func(path string, d fs.DirEntry, err error) error { if err != nil { - return errors.Wrap(err, "failed to create cloud build workflow") + return err } - - err = fs.WalkDir(workflowFS, ".", func(path string, d fs.DirEntry, err error) error { - if err != nil { - return err - } - if d.IsDir() { - if d.Name() != ".github" { - debugf(c.App.Writer, globalArgs.Debug, "\t\tCopying %s directory", d.Name()) - err = os.Mkdir(filepath.Join(destWorkflowPath, path), 0o750) - if err != nil { - return err - } - } - } else if !strings.HasPrefix(d.Name(), templatePrefix) { - debugf(c.App.Writer, globalArgs.Debug, "\t\tCopying file %s", path) - srcFile, err := templates.Open(filepath.Join(workflowPath, path)) + if d.IsDir() { + if d.Name() != ".github" { + debugf(c.App.Writer, globalArgs.Debug, "\t\tCopying %s directory", d.Name()) + err = os.Mkdir(filepath.Join(destWorkflowPath, path), 0o750) if err != nil { - return errors.Wrapf(err, "error opening file %s", srcFile) + return err } - defer utils.UncheckedErrorFunc(srcFile.Close) + } + } else if !strings.HasPrefix(d.Name(), templatePrefix) { + debugf(c.App.Writer, globalArgs.Debug, "\t\tCopying file %s", path) + srcFile, err := templates.Open(filepath.Join(workflowPath, path)) + if err != nil { + return errors.Wrapf(err, "error opening file %s", srcFile) + } + defer utils.UncheckedErrorFunc(srcFile.Close) - destPath := filepath.Join(destWorkflowPath, path) - //nolint:gosec - destFile, err := os.Create(destPath) - if err != nil { - return errors.Wrapf(err, "failed to create file %s", destPath) - } - defer utils.UncheckedErrorFunc(destFile.Close) + destPath := filepath.Join(destWorkflowPath, path) + //nolint:gosec + destFile, err := os.Create(destPath) + if err != nil { + return errors.Wrapf(err, "failed to create file %s", destPath) + } + defer utils.UncheckedErrorFunc(destFile.Close) - _, err = io.Copy(destFile, srcFile) - if err != nil { - return errors.Wrapf(err, "error executing template for %s", destPath) - } + _, err = io.Copy(destFile, srcFile) + if err != nil { + return errors.Wrapf(err, "error executing template for %s", destPath) } - return nil - }) - if err != nil { - return errors.Wrap(err, "failed to render all common files") } return nil + }) + if err != nil { + return errors.Wrap(err, "failed to render all common files") } - return nil } @@ -936,11 +926,7 @@ func renderManifest(c *cli.Context, moduleID string, module modulegen.ModuleInpu Path: "dist/archive.tar.gz", Arch: []string{"linux/amd64", "linux/arm64", "darwin/arm64", "windows/amd64"}, } - if module.EnableCloudBuild { - manifest.Entrypoint = "dist/main" - } else { - manifest.Entrypoint = "./run.sh" - } + manifest.Entrypoint = "dist/main" case golang: manifest.Build = &manifestBuildInfo{ Setup: "make setup", diff --git a/cli/module_generate/_templates/python/run.sh b/cli/module_generate/_templates/python/run.sh deleted file mode 100644 index 13527c28610..00000000000 --- a/cli/module_generate/_templates/python/run.sh +++ /dev/null @@ -1,13 +0,0 @@ -#!/bin/sh -cd `dirname $0` - -# Create a virtual environment to run our code -VENV_NAME="venv" -PYTHON="$VENV_NAME/bin/python" - -sh ./setup.sh - -# Be sure to use `exec` so that termination signals reach the python process, -# or handle forwarding termination signals manually -echo "Starting module..." -exec $PYTHON -m src.main $@ diff --git a/cli/module_generate/_templates/python/src/tmpl-main.py b/cli/module_generate/_templates/python/src/tmpl-main.py index ccf6b1dfa35..14ff7dd29e6 100644 --- a/cli/module_generate/_templates/python/src/tmpl-main.py +++ b/cli/module_generate/_templates/python/src/tmpl-main.py @@ -1,10 +1,6 @@ import asyncio from viam.module.module import Module -try: - from models.{{ .ModelSnake }} import {{ .ModelPascal }} -except ModuleNotFoundError: - # when running as local module with run.sh - from .models.{{ .ModelSnake }} import {{ .ModelPascal }} +from models.{{ .ModelSnake }} import {{ .ModelPascal }} if __name__ == '__main__': diff --git a/cli/module_generate/modulegen/inputs.go b/cli/module_generate/modulegen/inputs.go index 150bc94eece..768854aed4a 100644 --- a/cli/module_generate/modulegen/inputs.go +++ b/cli/module_generate/modulegen/inputs.go @@ -19,7 +19,6 @@ type ModuleInputs struct { ResourceType string `json:"resource_type"` ResourceSubtype string `json:"resource_subtype"` ModelName string `json:"model_name"` - EnableCloudBuild bool `json:"enable_cloud_build"` InitializeGit bool `json:"initialize_git"` RegisterOnApp bool `json:"-"` GeneratorVersion string `json:"generator_version"` diff --git a/cli/module_generate_test.go b/cli/module_generate_test.go index 88dc9a81101..d3f326f6b88 100644 --- a/cli/module_generate_test.go +++ b/cli/module_generate_test.go @@ -32,7 +32,6 @@ func TestGenerateModuleAction(t *testing.T) { ResourceType: "component", ResourceSubtype: "arm", ModelName: "my-model", - EnableCloudBuild: true, GeneratorVersion: "0.1.0", GeneratedOn: time.Now().UTC(), @@ -124,8 +123,6 @@ func TestGenerateModuleAction(t *testing.T) { test.That(t, err, test.ShouldBeNil) _, err = os.Stat(filepath.Join(modulePath, "setup.sh")) test.That(t, err, test.ShouldBeNil) - _, err = os.Stat(filepath.Join(modulePath, "run.sh")) - test.That(t, err, test.ShouldBeNil) _, err = os.Stat(filepath.Join(modulePath, ".gitignore")) test.That(t, err, test.ShouldBeNil) }) diff --git a/cli/profile.go b/cli/profile.go index e2a94ee1872..0fa9b6ef542 100644 --- a/cli/profile.go +++ b/cli/profile.go @@ -127,7 +127,7 @@ type removeProfileArgs struct { // if an env var profile isn't found, but return an error if a profile specified with the `--profile` // flag isn't found. func whichProfile(args *globalArgs) (*string, bool) { - // profile hasn't been specified for this command + // profile has been specified for this command if args.Profile != "" { return &args.Profile, true } diff --git a/components/camera/camera.go b/components/camera/camera.go index e7c3029fca3..9d3243dfdf9 100644 --- a/components/camera/camera.go +++ b/components/camera/camera.go @@ -177,18 +177,6 @@ type ImageMetadata struct { // A Camera is a resource that can capture frames. // For more information, see the [camera component docs]. // -// Image example: -// -// myCamera, err := camera.FromProvider(machine, "my_camera") -// imageBytes, mimeType, err := myCamera.Image(context.Background(), utils.MimeTypeJPEG, nil) -// -// Or try to directly decode as an image.Image: -// -// myCamera, err := camera.FromProvider(machine, "my_camera") -// img, err = camera.DecodeImageFromCamera(context.Background(), utils.MimeTypeJPEG, nil, myCamera) -// -// For more information, see the [Image method docs]. -// // Images example: // // myCamera, err := camera.FromProvider(machine, "my_camera") @@ -215,7 +203,6 @@ type ImageMetadata struct { // For more information, see the [Close method docs]. // // [camera component docs]: https://docs.viam.com/dev/reference/apis/components/camera/ -// [Image method docs]: https://docs.viam.com/dev/reference/apis/components/camera/#getimage // [Images method docs]: https://docs.viam.com/dev/reference/apis/components/camera/#getimages // [NextPointCloud method docs]: https://docs.viam.com/dev/reference/apis/components/camera/#getpointcloud // [Close method docs]: https://docs.viam.com/dev/reference/apis/components/camera/#close @@ -223,8 +210,7 @@ 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. + // Deprecated: Please utilize Images instead. Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) // Images is used for getting simultaneous images from different imagers, @@ -242,32 +228,32 @@ 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) +// DecodeImageFromCamera gets images from a camera resource and returns the first image as a decoded image.Image. +func DecodeImageFromCamera(ctx context.Context, cam Camera, filterSourceNames []string, extra map[string]interface{}) (image.Image, error) { + namedImages, _, err := cam.Images(ctx, filterSourceNames, extra) if err != nil { - return nil, fmt.Errorf("could not get image bytes from camera: %w", err) + return nil, fmt.Errorf("could not get images from camera: %w", err) } - if len(resBytes) == 0 { - return nil, errors.New("received empty bytes from camera") + if len(namedImages) == 0 { + return nil, errors.New("no images returned from camera") } - img, err := rimage.DecodeImage(ctx, resBytes, utils.WithLazyMIMEType(resMetadata.MimeType)) + img, err := namedImages[0].Image(ctx) 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. +// GetImageFromGetImages is a utility function to implement Image from an already-implemented Images 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. +// It uses the mimeType from the NamedImage to encode the bytes. // The extra parameter is passed through to the underlying Images method. +// Deprecated: This helper will be removed when Image method is fully removed. func GetImageFromGetImages( ctx context.Context, sourceName *string, @@ -332,6 +318,7 @@ func GetImageFromGetImages( // 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. +// Deprecated: This helper will be removed when Image method is fully removed. func GetImagesFromGetImage( ctx context.Context, mimeType string, diff --git a/components/camera/camera_test.go b/components/camera/camera_test.go index 6686ded2fbf..bb211255ac7 100644 --- a/components/camera/camera_test.go +++ b/components/camera/camera_test.go @@ -14,7 +14,6 @@ import ( "go.viam.com/rdk/components/camera" "go.viam.com/rdk/data" - "go.viam.com/rdk/logging" "go.viam.com/rdk/pointcloud" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -192,7 +191,7 @@ 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) + img, err := camera.DecodeImageFromCamera(context.Background(), noProj2, nil, nil) test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) @@ -240,10 +239,9 @@ 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) + img, err := camera.DecodeImageFromCamera(context.Background(), cam2, nil, nil) test.That(t, err, test.ShouldBeNil) - test.That(t, err, test.ShouldBeNil) test.That(t, img.Bounds().Dx(), test.ShouldEqual, 1280) test.That(t, img.Bounds().Dy(), test.ShouldEqual, 720) // cam2 should implement a default GetImages, that just returns the one image @@ -259,218 +257,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)) - annotations1 := data.Annotations{BoundingBoxes: []data.BoundingBox{{Label: "object1"}}} - annotations2 := data.Annotations{Classifications: []data.Classification{{Label: "object2"}}} - - 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, annotations1) - if err != nil { - return nil, resource.ResponseMetadata{}, err - } - namedImg2, err := camera.NamedImageFromImage(testImg2, source2Name, rutils.MimeTypeRawRGBA, annotations2) - 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, annotations1) - 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) - test.That(t, metadata.Annotations, test.ShouldResemble, annotations1) - 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, data.Annotations{}) - 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 8fc99ab3fe5..f0c062e5513 100644 --- a/components/camera/client.go +++ b/components/camera/client.go @@ -148,7 +148,7 @@ func (c *client) Stream( return } - img, err := DecodeImageFromCamera(streamCtx, mimeTypeFromCtx, nil, c) + img, err := DecodeImageFromCamera(streamCtx, c, nil, nil) if err != nil { for _, handler := range errHandlers { handler(streamCtx, err) @@ -176,6 +176,7 @@ func (c *client) Stream( } func (c *client) Image(ctx context.Context, mimeType string, extra map[string]interface{}) ([]byte, ImageMetadata, error) { + c.logger.CWarn(ctx, "Image (GetImage) is deprecated; please use Images (GetImages) instead") ctx, span := trace.StartSpan(ctx, "camera::client::Image") defer span.End() expectedType, _ := utils.CheckLazyMIMEType(mimeType) @@ -232,11 +233,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, data.AnnotationsFromProto(img.Annotations)) if err != nil { return nil, resource.ResponseMetadata{}, err diff --git a/components/camera/client_test.go b/components/camera/client_test.go index cd26efb4d92..7c539c24b20 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) @@ -120,14 +117,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 } @@ -151,14 +140,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, data.Annotations{}) + if err != nil { + return nil, resource.ResponseMetadata{}, err + } + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil } // bad camera injectCamera2 := &inject.Camera{} @@ -171,8 +162,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{ @@ -205,14 +200,11 @@ 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) + frame, err := camera.DecodeImageFromCamera(context.Background(), camera1Client, nil, nil) 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(), nil) test.That(t, err, test.ShouldBeNil) @@ -272,7 +264,7 @@ 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) + frame, err := camera.DecodeImageFromCamera(ctx, client, nil, nil) test.That(t, err, test.ShouldBeNil) dm, err := rimage.ConvertImageToDepthMap(context.Background(), frame) test.That(t, err, test.ShouldBeNil) @@ -288,7 +280,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()) @@ -302,51 +294,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) @@ -642,97 +589,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 224737ea9a4..abe7ec0f47b 100644 --- a/components/camera/collectors.go +++ b/components/camera/collectors.go @@ -111,7 +111,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. @@ -122,15 +122,42 @@ 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, - Annotations: metadata.Annotations, + Annotations: img.Annotations, + Payload: imgBytes, }}), nil }) return data.NewCollector(cFunc, params) diff --git a/components/camera/collectors_test.go b/components/camera/collectors_test.go index fab67d24638..ba0dfba0ec5 100644 --- a/components/camera/collectors_test.go +++ b/components/camera/collectors_test.go @@ -107,7 +107,8 @@ func TestCollectors(t *testing.T) { collector: camera.NewReadImageCollector, expected: []*datasyncpb.SensorData{{ Metadata: &datasyncpb.SensorMetadata{ - MimeType: datasyncpb.MimeType_MIME_TYPE_IMAGE_JPEG, + MimeType: datasyncpb.MimeType_MIME_TYPE_IMAGE_JPEG, + Annotations: &v1.Annotations{Classifications: []*v1.Classification{{Label: "add_annotations"}}}, }, Data: &datasyncpb.SensorData_Binary{Binary: viamLogoJpeg}, }}, @@ -190,13 +191,6 @@ 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) { - viamLogoJpegBytes, err := io.ReadAll(base64.NewDecoder(base64.StdEncoding, bytes.NewReader(viamLogoJpegB64))) - if err != nil { - return nil, camera.ImageMetadata{}, err - } - return viamLogoJpegBytes, camera.ImageMetadata{MimeType: mimeType}, nil - } v.NextPointCloudFunc = func(ctx context.Context, extra map[string]interface{}) (pointcloud.PointCloud, error) { return pcd, nil diff --git a/components/camera/fake/camera_test.go b/components/camera/fake/camera_test.go index 9c8f44088a4..a5eaa46dd7f 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,7 @@ 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) + img, err := camera.DecodeImageFromCamera(context.Background(), cam, nil, nil) 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 2ae9d5dcad0..f1934f691c2 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..fe911806c2f 100644 --- a/components/camera/ffmpeg/ffmpeg_test.go +++ b/components/camera/ffmpeg/ffmpeg_test.go @@ -10,7 +10,6 @@ import ( "go.viam.com/rdk/components/camera" "go.viam.com/rdk/logging" - "go.viam.com/rdk/utils" ) func TestFFMPEGCamera(t *testing.T) { @@ -21,7 +20,7 @@ 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) + _, err = camera.DecodeImageFromCamera(ctx, cam, nil, nil) test.That(t, err, test.ShouldBeNil) } test.That(t, cam.Close(context.Background()), test.ShouldBeNil) diff --git a/components/camera/replaypcd/replaypcd.go b/components/camera/replaypcd/replaypcd.go index 2c977b0fe77..beff0486f85 100644 --- a/components/camera/replaypcd/replaypcd.go +++ b/components/camera/replaypcd/replaypcd.go @@ -337,6 +337,10 @@ func (replay *pcdCamera) Images( return nil, resource.ResponseMetadata{}, errors.New("Images 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") +} + // Properties is a part of the camera interface and returns the camera.Properties struct with SupportsPCD set to true. func (replay *pcdCamera) Properties(ctx context.Context) (camera.Properties, error) { props := camera.Properties{ @@ -351,10 +355,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 35df5ee75f1..6dc205b27ec 100644 --- a/components/camera/server.go +++ b/components/camera/server.go @@ -47,6 +47,7 @@ func (s *serviceServer) GetImage( ctx context.Context, req *pb.GetImageRequest, ) (*pb.GetImageResponse, error) { + s.logger.CWarn(ctx, "GetImage is deprecated; please use GetImages instead") ctx, span := trace.StartSpan(ctx, "camera::server::GetImage") defer span.End() cam, err := s.coll.Resource(req.Name) @@ -127,10 +128,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, Annotations: img.Annotations.ToProto(), @@ -148,10 +147,12 @@ func (s *serviceServer) GetImages( // 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. +// Deprecated: Use GetImages instead. func (s *serviceServer) RenderFrame( ctx context.Context, req *pb.RenderFrameRequest, ) (*httpbody.HttpBody, error) { + s.logger.CWarn(ctx, "RenderFrame is deprecated; please use GetImages instead") ctx, span := trace.StartSpan(ctx, "camera::server::RenderFrame") defer span.End() if req.MimeType == "" { diff --git a/components/camera/server_test.go b/components/camera/server_test.go index 63a4500b5c8..1315009ab37 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, data.Annotations{}) 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, extra map[string]interface{}) (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) @@ -418,9 +228,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 @@ -429,7 +239,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) @@ -442,7 +252,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) @@ -466,14 +276,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) @@ -537,80 +347,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, @@ -701,25 +437,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 65d6c6f6a80..a0bf87febbd 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 d610de13152..f16b150847c 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,13 +137,11 @@ 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) + img, err := camera.DecodeImageFromCamera(ctx, source, nil, nil) var streamType camera.ImageType if err != nil { streamType = camera.UnspecifiedStream - } else if _, ok := img.(*rimage.DepthMap); ok { - streamType = camera.DepthStream } else if _, ok := img.(*image.Gray16); ok { streamType = camera.DepthStream } else { @@ -189,7 +186,7 @@ type transformPipeline struct { func (tp transformPipeline) Read(ctx context.Context) (image.Image, func(), error) { ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::Read") defer span.End() - img, err := camera.DecodeImageFromCamera(ctx, "", nil, tp.src) + img, err := camera.DecodeImageFromCamera(ctx, tp.src, nil, nil) if err != nil { return nil, func() {}, err } diff --git a/components/camera/transformpipeline/pipeline_test.go b/components/camera/transformpipeline/pipeline_test.go index 4dbfb97ef4d..c62713f0213 100644 --- a/components/camera/transformpipeline/pipeline_test.go +++ b/components/camera/transformpipeline/pipeline_test.go @@ -37,7 +37,7 @@ 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) + inImg, err := camera.DecodeImageFromCamera(context.Background(), src, nil, nil) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) @@ -83,7 +83,7 @@ func TestTransformPipelineDepth(t *testing.T) { source := gostream.NewVideoSource(&fake.StaticSource{DepthImg: dm}, prop.Video{}) src, err := camera.WrapVideoSourceWithProjector(context.Background(), source, nil, camera.DepthStream) test.That(t, err, test.ShouldBeNil) - inImg, err := camera.DecodeImageFromCamera(context.Background(), "", nil, src) + inImg, err := camera.DecodeImageFromCamera(context.Background(), src, nil, nil) test.That(t, err, test.ShouldBeNil) test.That(t, inImg.Bounds().Dx(), test.ShouldEqual, 128) test.That(t, inImg.Bounds().Dy(), test.ShouldEqual, 72) diff --git a/components/camera/videosource/webcam.go b/components/camera/videosource/webcam.go index 744606ac7e4..6eaa4b0d423 100644 --- a/components/camera/videosource/webcam.go +++ b/components/camera/videosource/webcam.go @@ -379,6 +379,7 @@ func (c *webcam) Images(_ context.Context, _ []string, _ map[string]interface{}) } func (c *webcam) Image(ctx context.Context, _ string, extra map[string]interface{}) ([]byte, camera.ImageMetadata, error) { + c.logger.CWarn(ctx, "Image (GetImage) is deprecated; please use Images (GetImages) instead") imgBytes, resMetadata, err := camera.GetImageFromGetImages(ctx, nil, c, extra, nil) if err != nil { return nil, camera.ImageMetadata{}, err diff --git a/data/collector_types.go b/data/collector_types.go index 17c6b5cd404..ebb84474100 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" @@ -283,26 +282,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 { @@ -321,18 +300,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 bab8dc9ca3f..50ef2e3fe5e 100644 --- a/data/collector_types_test.go +++ b/data/collector_types_test.go @@ -10,7 +10,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" @@ -345,14 +344,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/etc/lint_register_apis.sh b/etc/lint_register_apis.sh index a942d98cdc6..82b91152621 100755 --- a/etc/lint_register_apis.sh +++ b/etc/lint_register_apis.sh @@ -1,7 +1,20 @@ #!/usr/bin/env bash -# Ensures that all component and service APIs have a corresponding import line in 'rdk/[services|components]/register_apis/all.go'. +# Ensures that all component and service APIs have a corresponding import line +# in 'rdk/[services|components]/register_apis/all.go'. +# The directories in the `pkgs` array contain packages that register API models +# with go init functions. This script will verify that all such packages have +# underscore imports in the corresponding `register_apis` subpackage, which +# provides a convenient way for modules and other client code to register all +# known API models with fewer imports. pkgs=(components services) + +# `cgo_paths` contains a list of packages that register API models but depend +# on cgo. For these packages we invert the usual logic: cgo packages should +# _not_ be included in the `register_apis` package so that the `register_apis` +# package can be used by modules and other client code without imposing a +# dependency on cgo, further requiring installed libraries and properly +# configured CGO_... environment variables for Go compilation to succeed. cgo_paths=(services/motion services/vision components/camera components/audioinput) for p in "${pkgs[@]}"; do @@ -18,7 +31,7 @@ for p in "${pkgs[@]}"; do break fi done - if $is_cgo_path; then + if $is_cgo_path; then if grep -Fq "$expectedImport" register_apis/* 2>/dev/null; then echo "Detected restricted cgo import '$expectedImport' in 'rdk/$p/register_apis'" exit 1 diff --git a/examples/customresources/demos/multiplemodules/moduletest/module_test.go b/examples/customresources/demos/multiplemodules/moduletest/module_test.go index 8dea0339ee4..552f1219749 100644 --- a/examples/customresources/demos/multiplemodules/moduletest/module_test.go +++ b/examples/customresources/demos/multiplemodules/moduletest/module_test.go @@ -34,11 +34,7 @@ import ( func TestMultipleModules(t *testing.T) { logger, observer := logging.NewObservedTestLogger(t) - // testViamHome := t.TempDir() - testViamHome, _ := os.MkdirTemp("", "") - t.Cleanup(func() { - t.Logf("VIAM TEST HOME: %v", testViamHome) - }) + testViamHome := t.TempDir() var port int success := false for portTryNum := 0; portTryNum < 10; portTryNum++ { diff --git a/logging/noop_event_logger.go b/logging/noop_event_logger.go index 6aff9734480..29356266daf 100644 --- a/logging/noop_event_logger.go +++ b/logging/noop_event_logger.go @@ -4,4 +4,4 @@ package logging // RegisterEventLogger does nothing on Unix. On Windows it will add an `Appender` for logging to // windows event system. -func RegisterEventLogger(rootLogger Logger) {} +func RegisterEventLogger(rootLogger Logger, name string) {} diff --git a/logging/windows_event_logger.go b/logging/windows_event_logger.go index 8e8d8a1651f..2281cd557b2 100644 --- a/logging/windows_event_logger.go +++ b/logging/windows_event_logger.go @@ -11,8 +11,8 @@ import ( // RegisterEventLogger does nothing on Unix. On Windows it will add an `Appender` for logging to // windows event system. -func RegisterEventLogger(rootLogger Logger) { - log, err := eventlog.Open("viam-server") +func RegisterEventLogger(rootLogger Logger, name string) { + log, err := eventlog.Open(name) if err != nil { rootLogger.Errorw("Unable to open windows event log", "err", err) } else { diff --git a/logging/windows_logging_test.go b/logging/windows_logging_test.go index 322e584ab30..436f3126b1e 100644 --- a/logging/windows_logging_test.go +++ b/logging/windows_logging_test.go @@ -1,4 +1,5 @@ //go:build windows + package logging import ( @@ -9,7 +10,7 @@ import ( func TestWindowsNulls(t *testing.T) { logger := NewLogger("nulls") - RegisterEventLogger(logger) + RegisterEventLogger(logger, "viam-server") logger.Info("this \x00 is a null") err := logger.Sync() test.That(t, err, test.ShouldBeNil) diff --git a/robot/client/client_test.go b/robot/client/client_test.go index 5839f38e63c..a595fdbd174 100644 --- a/robot/client/client_test.go +++ b/robot/client/client_test.go @@ -53,6 +53,7 @@ import ( "go.viam.com/rdk/components/sensor" "go.viam.com/rdk/components/servo" "go.viam.com/rdk/config" + "go.viam.com/rdk/data" rgrpc "go.viam.com/rdk/grpc" "go.viam.com/rdk/logging" "go.viam.com/rdk/operation" @@ -347,8 +348,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, data.Annotations{}) + if err != nil { + return nil, resource.ResponseMetadata{}, err + } + return []camera.NamedImage{namedImg}, resource.ResponseMetadata{CapturedAt: time.Now()}, nil } injectInputDev := &inject.InputController{} @@ -523,11 +532,11 @@ func TestStatusClient(t *testing.T) { camera1, err := camera.FromProvider(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.FromProvider(client, "gripper1") test.That(t, err, test.ShouldBeNil) @@ -604,7 +613,7 @@ func TestStatusClient(t *testing.T) { camera1, err = camera.FromProvider(client, "camera1") test.That(t, err, test.ShouldBeNil) - frame, err := camera.DecodeImageFromCamera(context.Background(), rutils.MimeTypeRawRGBA, nil, camera1) + frame, err := camera.DecodeImageFromCamera(context.Background(), camera1, nil, nil) 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 56ecedb9029..607fa56d176 100644 --- a/robot/impl/local_robot_test.go +++ b/robot/impl/local_robot_test.go @@ -92,10 +92,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 a3c4d171645..8a80be8d0b7 100644 --- a/robot/web/stream/camera/camera.go +++ b/robot/web/stream/camera/camera.go @@ -2,16 +2,58 @@ package camera import ( + "bytes" "context" + "fmt" "image" "github.com/pion/mediadevices/pkg/prop" "go.viam.com/rdk/components/camera" "go.viam.com/rdk/gostream" + "go.viam.com/rdk/rimage" "go.viam.com/rdk/robot" + rutils "go.viam.com/rdk/utils" ) +// StreamableImageMIMETypes is the set of all mime types the stream server supports. +// StreamableImageMIMETypes represents all mime types the stream server supports. +// The order of the slice defines the priority of the mime types. +var StreamableImageMIMETypes = []string{ + rutils.MimeTypeJPEG, + rutils.MimeTypePNG, + rutils.MimeTypeRawRGBA, + rutils.MimeTypeRawDepth, + rutils.MimeTypeQOI, +} + +// 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) { @@ -24,14 +66,119 @@ func Camera(robot robot.Robot, stream gostream.Stream) (camera.Camera, error) { return cam, nil } +// FormatStringToMimeType takes a format string returned from image.DecodeConfig and converts +// it to a utils mime type. +func FormatStringToMimeType(format string) string { + return fmt.Sprintf("image/%s", format) +} + +// GetStreamableNamedImageFromCamera returns the first named image it finds from the camera that is supported for streaming. +// It prioritizes images based on the order of StreamableImageMIMETypes. +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 _, streamableMimeType := range StreamableImageMIMETypes { + for _, namedImage := range namedImages { + if namedImage.MimeType() == streamableMimeType { + return namedImage, nil + } + + imgBytes, err := namedImage.Bytes(ctx) + if err != nil { + continue + } + + _, format, err := image.DecodeConfig(bytes.NewReader(imgBytes)) + if err != nil { + continue + } + if FormatStringToMimeType(format) == streamableMimeType { + 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 }) diff --git a/robot/web/stream/camera/camera_test.go b/robot/web/stream/camera/camera_test.go index 1b9b899be3f..bac3d380cbc 100644 --- a/robot/web/stream/camera/camera_test.go +++ b/robot/web/stream/camera/camera_test.go @@ -1,27 +1,285 @@ package camera_test import ( + "bytes" "context" + "errors" + "fmt" "image" "testing" "go.viam.com/test" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/data" "go.viam.com/rdk/gostream" + "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" camerautils "go.viam.com/rdk/robot/web/stream/camera" "go.viam.com/rdk/testutils/inject" "go.viam.com/rdk/utils" ) +func TestFormatStringToMimeType(t *testing.T) { + testRect := image.Rect(0, 0, 100, 100) + + type testCase struct { + mimeType string + createImage func() image.Image + expectedFormat string + } + + testCases := []testCase{ + { + mimeType: utils.MimeTypeRawRGBA, + createImage: func() image.Image { + return image.NewRGBA(testRect) + }, + expectedFormat: "vnd.viam.rgba", + }, + { + mimeType: utils.MimeTypeRawDepth, + createImage: func() image.Image { + return image.NewGray16(testRect) + }, + expectedFormat: "vnd.viam.dep", + }, + { + mimeType: utils.MimeTypeJPEG, + createImage: func() image.Image { + return image.NewRGBA(testRect) + }, + expectedFormat: "jpeg", + }, + { + mimeType: utils.MimeTypePNG, + createImage: func() image.Image { + return image.NewRGBA(testRect) + }, + expectedFormat: "png", + }, + { + mimeType: utils.MimeTypeQOI, + createImage: func() image.Image { + return image.NewRGBA(testRect) + }, + expectedFormat: "qoi", + }, + } + + for _, tc := range testCases { + t.Run(tc.mimeType, func(t *testing.T) { + sourceImg := tc.createImage() + imgBytes, err := rimage.EncodeImage(context.Background(), sourceImg, tc.mimeType) + test.That(t, err, test.ShouldBeNil) + + _, format, err := image.DecodeConfig(bytes.NewReader(imgBytes)) + test.That(t, err, test.ShouldBeNil) + test.That(t, format, test.ShouldEqual, tc.expectedFormat) + + resultMimeType := camerautils.FormatStringToMimeType(format) + test.That(t, resultMimeType, test.ShouldEqual, tc.mimeType) + + var ok bool + for _, m := range camerautils.StreamableImageMIMETypes { + if m == resultMimeType { + ok = true + break + } + } + test.That(t, ok, test.ShouldBeTrue) + }) + } +} + +func TestGetStreamableNamedImageFromCamera(t *testing.T) { + sourceImg := image.NewRGBA(image.Rect(0, 0, 1, 1)) + unstreamableImg, err := camera.NamedImageFromImage(sourceImg, "unstreamable", "image/undefined", data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG, data.Annotations{}) + 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) + }) + + t.Run("all streamable mime types are accepted", func(t *testing.T) { + sourceImg := image.NewRGBA(image.Rect(0, 0, 1, 1)) + + streamableMIMETypes := camerautils.StreamableImageMIMETypes + + for _, mimeType := range streamableMIMETypes { + t.Run(mimeType, func(t *testing.T) { + streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", mimeType, data.Annotations{}) + 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{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") + test.That(t, img.MimeType(), test.ShouldEqual, mimeType) + }) + } + }) + + t.Run("image.DecodeConfig fails and continues to next streamable image", func(t *testing.T) { + malformedBytes := []byte("malformed") + + malformedNamedImage, err := camera.NamedImageFromBytes(malformedBytes, "malformed", "image/wtf", data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + + goodImg := image.NewRGBA(image.Rect(0, 0, 2, 2)) + goodImgBytes, err := rimage.EncodeImage(context.Background(), goodImg, utils.MimeTypeJPEG) + test.That(t, err, test.ShouldBeNil) + streamableNamedImage, err := camera.NamedImageFromBytes(goodImgBytes, "good", "image/wtf", data.Annotations{}) + 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{malformedNamedImage, streamableNamedImage}, resource.ResponseMetadata{}, nil + }, + } + + img, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + test.That(t, img.SourceName, test.ShouldEqual, "good") + resBytes, err := img.Bytes(context.Background()) + test.That(t, err, test.ShouldBeNil) + test.That(t, resBytes, test.ShouldResemble, goodImgBytes) + }) + + t.Run("prioritizes images based on StreamableImageMIMETypes order", func(t *testing.T) { + sourceImg := image.NewRGBA(image.Rect(0, 0, 1, 1)) + // PNG is higher priority than Depth in our slice + depthImg, err := camera.NamedImageFromImage(sourceImg, "depth", utils.MimeTypeRawDepth, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + pngImg, err := camera.NamedImageFromImage(sourceImg, "png", utils.MimeTypePNG, data.Annotations{}) + 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 depth first, but PNG should be selected as it's higher priority + return []camera.NamedImage{depthImg, pngImg}, resource.ResponseMetadata{}, nil + }, + } + img, err := camerautils.GetStreamableNamedImageFromCamera(context.Background(), cam) + test.That(t, err, test.ShouldBeNil) + test.That(t, img.SourceName, test.ShouldEqual, "png") + test.That(t, img.MimeType(), test.ShouldEqual, utils.MimeTypePNG) + + camReverse := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + // Return PNG first, still should be PNG + return []camera.NamedImage{pngImg, depthImg}, resource.ResponseMetadata{}, nil + }, + } + img, err = camerautils.GetStreamableNamedImageFromCamera(context.Background(), camReverse) + test.That(t, err, test.ShouldBeNil) + test.That(t, img.SourceName, test.ShouldEqual, "png") + test.That(t, img.MimeType(), test.ShouldEqual, utils.MimeTypePNG) + }) +} + 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, data.Annotations{}) + 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) @@ -39,9 +297,13 @@ func TestVideoSourceFromCamera(t *testing.T) { } func TestVideoSourceFromCameraFalsyVideoProps(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 + cam := &inject.Camera{ + ImagesFunc: func( + ctx context.Context, + sourceNames []string, + extra map[string]interface{}, + ) ([]camera.NamedImage, resource.ResponseMetadata, error) { + return nil, resource.ResponseMetadata{}, errors.New("this should not be called") }, } @@ -50,7 +312,7 @@ func TestVideoSourceFromCameraFalsyVideoProps(t *testing.T) { // See: https://viam.atlassian.net/browse/RSDK-12744 // // Instead, it should return a VideoSource with empty video props. - vs, err := camerautils.VideoSourceFromCamera(context.Background(), malformedCam) + vs, err := camerautils.VideoSourceFromCamera(context.Background(), cam) test.That(t, err, test.ShouldBeNil) test.That(t, vs, test.ShouldNotBeNil) @@ -63,23 +325,539 @@ func TestVideoSourceFromCameraFalsyVideoProps(t *testing.T) { } 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", data.Annotations{}) + 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", data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG, data.Annotations{}) + 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, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + fallbackNamedImage, err := camera.NamedImageFromImage(sourceImg2, "fallback", utils.MimeTypeJPEG, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + + goodSourceCallCount := 0 + 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 goodSourceCallCount == 0 { + return []camera.NamedImage{goodNamedImage}, resource.ResponseMetadata{}, nil + } + return []camera.NamedImage{fallbackNamedImage}, resource.ResponseMetadata{}, nil + } + + // getImageBySourceName call + if sourceNames[0] == "good" { + goodSourceCallCount++ + if goodSourceCallCount == 1 { + return nil, resource.ResponseMetadata{}, errors.New("source 'good' is gone") + } + return nil, resource.ResponseMetadata{}, fmt.Errorf("unexpected call to source 'good' after failure") + } + 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, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + namedB, err := camera.NamedImageFromImage(imageGood2, "good2", utils.MimeTypeJPEG, data.Annotations{}) + 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) + + // JPEG is higher priority than PNG in StreamableImageMIMETypes img, _, err := stream.Next(context.Background()) test.That(t, err, test.ShouldBeNil) - test.That(t, img, test.ShouldNotBeNil) + diffVal, _, err := rimage.CompareImages(img, imageGood2) + 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", data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + unstream2, err := camera.NamedImageFromImage(src, "bad2", "image/undefined", data.Annotations{}) + 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, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + fallback, err := camera.NamedImageFromImage(src, "fallback", utils.MimeTypePNG, data.Annotations{}) + 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() selects "good" source + 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) + // Second Next() tries to get "good" but filter returns no images; expect failure + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New("no images found for requested source name: good")) + // Third 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, data.Annotations{}) + 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, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + img2, err := camera.NamedImageFromImage(src, "source2", utils.MimeTypeRawRGBA, data.Annotations{}) + 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) + + // First Next() performs unfiltered selection and picks "source1" + 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) + + // Second Next() requests "source1" but receives 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"]`)) + + // Third Next() 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, data.Annotations{}) + 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, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + validNamed, err := camera.NamedImageFromImage(validImg, "good", utils.MimeTypePNG, data.Annotations{}) + 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, data.Annotations{}) + test.That(t, err, test.ShouldBeNil) + mismatched, err := camera.NamedImageFromImage(src, "bad", utils.MimeTypePNG, data.Annotations{}) + 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(): unfiltered selection picks "good" + 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) + // Second Next(): filtered request for "good" returns mismatched source name and should fail + _, _, err = stream.Next(context.Background()) + test.That(t, err, test.ShouldBeError, errors.New(`mismatched source name: requested "good", got "bad"`)) + // Third 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, data.Annotations{}) + 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)) } diff --git a/robot/web/stream/camera2/camera.go b/robot/web/stream/camera2/camera.go deleted file mode 100644 index 60cc367227e..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.FromProvider(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 bd24c65a876..00000000000 --- a/robot/web/stream/camera2/camera_test.go +++ /dev/null @@ -1,691 +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/data" - "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", data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG, data.Annotations{}) - 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, data.Annotations{}) - 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, data.Annotations{}) - 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", data.Annotations{}) - 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", data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - streamableImg, err := camera.NamedImageFromImage(sourceImg, "streamable", utils.MimeTypePNG, data.Annotations{}) - 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, data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - fallbackNamedImage, err := camera.NamedImageFromImage(sourceImg2, "fallback", utils.MimeTypeJPEG, data.Annotations{}) - 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, data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - namedB, err := camera.NamedImageFromImage(imageGood2, "good2", utils.MimeTypeJPEG, data.Annotations{}) - 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", data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - unstream2, err := camera.NamedImageFromImage(src, "bad2", "image/undefined", data.Annotations{}) - 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, data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - fallback, err := camera.NamedImageFromImage(src, "fallback", utils.MimeTypePNG, data.Annotations{}) - 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, data.Annotations{}) - 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, data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - img2, err := camera.NamedImageFromImage(src, "source2", utils.MimeTypeRawRGBA, data.Annotations{}) - 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, data.Annotations{}) - 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, data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - validNamed, err := camera.NamedImageFromImage(validImg, "good", utils.MimeTypePNG, data.Annotations{}) - 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, data.Annotations{}) - test.That(t, err, test.ShouldBeNil) - mismatched, err := camera.NamedImageFromImage(src, "bad", utils.MimeTypePNG, data.Annotations{}) - 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, data.Annotations{}) - 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 b155d0f16a0..285b5f8ce72 100644 --- a/robot/web/stream/server.go +++ b/robot/web/stream/server.go @@ -3,7 +3,6 @@ package webstream import ( "context" "fmt" - "image" "runtime" "sync" "time" @@ -22,8 +21,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 +170,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.FromProvider(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 +271,7 @@ func (server *Server) RemoveStream(ctx context.Context, req *streampb.RemoveStre streamName := streamToRemove.Stream.Name() _, isAudioResourceErr := audioinput.FromProvider(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 @@ -419,7 +417,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) } @@ -451,7 +449,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) } @@ -643,7 +641,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 @@ -794,56 +792,9 @@ 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) { - if rutils.GetImagesInStreamServer() { - return sampleFrameSize2(ctx, cam, logger) - } - return sampleFrameSize1(ctx, cam, logger) -} - -func sampleFrameSize1(ctx context.Context, cam camera.Camera, logger logging.Logger) (int, int, error) { - logger.Debug("sampling frame size") - // Attempt to get a frame from the stream with a maximum of 5 retries. - // This is useful if cameras have a warm-up period before they can start streaming. - var frame image.Image - var err error -retryLoop: - for i := 0; i < 5; i++ { - select { - 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. - } - logger.Debugf("failed to get frame, retrying... (%d/5)", i+1) - time.Sleep(retryDelay) - } - } - if err != nil { - return 0, 0, fmt.Errorf("failed to get frame after 5 attempts: %w", err) - } - return frame.Bounds().Dx(), frame.Bounds().Dy(), nil -} - -func sampleFrameSize2(ctx context.Context, cam camera.Camera, logger logging.Logger) (int, int, error) { logger.Debug("sampling frame size") // Attempt to get a frame from the stream with a maximum of 5 retries. // This is useful if cameras have a warm-up period before they can start streaming. @@ -854,7 +805,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..7189f182c5a 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, data.Annotations{}) + 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 aaab19e3e78..fab504f006b 100644 --- a/services/datamanager/builtin/builtin_test.go +++ b/services/datamanager/builtin/builtin_test.go @@ -471,16 +471,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, utils.MimeTypeJPEG) 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, "", utils.MimeTypeJPEG, data.Annotations{}) + 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 34321fc387c..9c2406e2d56 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 57678821a87..d6d9537f66a 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 f955f458ac5..eb78d80b106 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 1abb334d4cf..456b1011d9a 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 a19eef83741..6c57212d63a 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..f4f2e803286 100644 --- a/services/vision/vision_service_builder_test.go +++ b/services/vision/vision_service_builder_test.go @@ -5,10 +5,12 @@ import ( "errors" "image" "testing" + "time" "go.viam.com/test" "go.viam.com/rdk/components/camera" + "go.viam.com/rdk/data" "go.viam.com/rdk/logging" "go.viam.com/rdk/resource" "go.viam.com/rdk/rimage" @@ -63,11 +65,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, data.Annotations{}) + 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 3abc0c7b9c5..24b9a9e9ca7 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, extra map[string]interface{ 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/testutils/robottestutils/robot_utils.go b/testutils/robottestutils/robot_utils.go index 2387437021c..c58353978cd 100644 --- a/testutils/robottestutils/robot_utils.go +++ b/testutils/robottestutils/robot_utils.go @@ -141,11 +141,14 @@ func ServerAsSeparateProcess(t *testing.T, cfgFileName string, logger logging.Lo args := []string{"-config", cfgFileName} cfg.processConfig = pexec.ProcessConfig{ - Name: serverPath, - Args: args, - CWD: utils.ResolveFile("./"), - Environment: map[string]string{"HOME": testTempHome}, - Log: true, + Name: serverPath, + Args: args, + CWD: utils.ResolveFile("./"), + Environment: map[string]string{ + "HOME": testTempHome, // *NIX + "USERPROFILE": testTempHome, // Windows + }, + Log: true, } for _, opt := range opts { opt(&cfg) diff --git a/utils/env.go b/utils/env.go index 31eab44c458..05b99456090 100644 --- a/utils/env.go +++ b/utils/env.go @@ -6,7 +6,6 @@ import ( "path/filepath" "regexp" "runtime" - "slices" "strconv" "strings" "time" @@ -80,9 +79,6 @@ const ( // defaults to 100. ViamResourceRequestsLimitEnvVar = "VIAM_RESOURCE_REQUESTS_LIMIT" - // GetImagesInStreamServerEnvVar is the environment variable that enables the GetImages feature flag in stream server. - GetImagesInStreamServerEnvVar = "VIAM_GET_IMAGES_IN_STREAM_SERVER" - // ViamModuleTracingEnvVar is the environment variable that configures // modules to record trace spans and send them to their parent viam-server // process. Any non-empty string other than "0" or "false" enables module @@ -214,11 +210,6 @@ func GetenvBool(v string, def bool) bool { return x[0] == 't' || x[0] == 'T' || x[0] == '1' } -// GetImagesInStreamServer returns true iff an env bool was set to use the GetImages feature flag in stream server. -func GetImagesInStreamServer() bool { - return slices.Contains(EnvTrueValues, os.Getenv(GetImagesInStreamServerEnvVar)) -} - // CleanWindowsSocketPath mutates socket paths on windows only so they // work well with the GRPC library. // It converts e.g. C:\x\y.sock to /x/y.sock diff --git a/utils/mime.go b/utils/mime.go index 51c56b9a4f9..f286cb81248 100644 --- a/utils/mime.go +++ b/utils/mime.go @@ -68,7 +68,8 @@ func CheckLazyMIMEType(mimeType string) (string, bool) { return mimeType, false } -// MimeTypeToFormat maps Mymetype to Format. +// MimeTypeToFormat maps Mimetype to Format. +// Deprecated: This will be removed when the Format field is removed from the proto. var MimeTypeToFormat = map[string]camerapb.Format{ MimeTypeJPEG: camerapb.Format_FORMAT_JPEG, MimeTypePNG: camerapb.Format_FORMAT_PNG, @@ -77,7 +78,8 @@ var MimeTypeToFormat = map[string]camerapb.Format{ "": camerapb.Format_FORMAT_UNSPECIFIED, } -// FormatToMimeType maps Format to Mymetype. +// FormatToMimeType maps Format to Mimetype. +// Deprecated: This will be removed when the Format field is removed from the proto. var FormatToMimeType = map[camerapb.Format]string{ camerapb.Format_FORMAT_JPEG: MimeTypeJPEG, camerapb.Format_FORMAT_PNG: MimeTypePNG, diff --git a/web/server/entrypoint.go b/web/server/entrypoint.go index 391fc888bf5..1de6e87d686 100644 --- a/web/server/entrypoint.go +++ b/web/server/entrypoint.go @@ -165,7 +165,7 @@ func RunServer(ctx context.Context, args []string, _ logging.Logger) (err error) registry.AddAppenderToAll(logging.NewStdoutAppender()) } - logging.RegisterEventLogger(rootLogger) + logging.RegisterEventLogger(rootLogger, "viam-server") config.InitLoggingSettings(rootLogger, configLogger, argsParsed.Debug) if argsParsed.Version {