Skip to content

Commit e2f055d

Browse files
committed
Fix signatures when extra isn't used
1 parent cb4d6d6 commit e2f055d

File tree

6 files changed

+7
-7
lines changed

6 files changed

+7
-7
lines changed

components/camera/fake/camera.go

+1-1
Original file line numberDiff line numberDiff line change
@@ -226,7 +226,7 @@ func (c *Camera) Read(ctx context.Context) (image.Image, func(), error) {
226226
}
227227

228228
// PointCloud always returns a pointcloud of a yellow to blue gradient, with the depth determined by the intensity of blue.
229-
func (c *Camera) PointCloud(ctx context.Context, extra map[string]interface{}) (pointcloud.PointCloud, error) {
229+
func (c *Camera) PointCloud(ctx context.Context, _ map[string]interface{}) (pointcloud.PointCloud, error) {
230230
if c.cachePointCloud != nil {
231231
return c.cachePointCloud, nil
232232
}

components/camera/fake/image_file.go

+2-2
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ func (fs *fileSource) Images(ctx context.Context) ([]camera.NamedImage, resource
147147

148148
// PointCloud returns the point cloud from projecting the rgb and depth image using the intrinsic parameters,
149149
// or the pointcloud from file if set.
150-
func (fs *fileSource) PointCloud(ctx context.Context, extra map[string]interface{}) (pointcloud.PointCloud, error) {
150+
func (fs *fileSource) PointCloud(ctx context.Context, _ map[string]interface{}) (pointcloud.PointCloud, error) {
151151
if fs.PointCloudFN != "" {
152152
return pointcloud.NewFromFile(fs.PointCloudFN, nil)
153153
}
@@ -208,7 +208,7 @@ func (ss *StaticSource) Images(ctx context.Context) ([]camera.NamedImage, resour
208208
}
209209

210210
// PointCloud returns the point cloud from projecting the rgb and depth image using the intrinsic parameters.
211-
func (ss *StaticSource) PointCloud(ctx context.Context, extra map[string]interface{}) (pointcloud.PointCloud, error) {
211+
func (ss *StaticSource) PointCloud(ctx context.Context, _ map[string]interface{}) (pointcloud.PointCloud, error) {
212212
if ss.Proj == nil {
213213
return nil, transform.NewNoIntrinsicsError("camera intrinsics not found in config")
214214
}

components/camera/replaypcd/replaypcd.go

+1-1
Original file line numberDiff line numberDiff line change
@@ -166,7 +166,7 @@ func newPCDCamera(
166166
}
167167

168168
// PointCloud returns the next point cloud retrieved from cloud storage based on the applied filter.
169-
func (replay *pcdCamera) PointCloud(ctx context.Context, extra map[string]interface{}) (pointcloud.PointCloud, error) {
169+
func (replay *pcdCamera) PointCloud(ctx context.Context, _ map[string]interface{}) (pointcloud.PointCloud, error) {
170170
// First acquire the lock, so that it's safe to populate the cache and/or retrieve and
171171
// remove the next data point from the cache. Note that if multiple threads call
172172
// PointCloud concurrently, they may get data out-of-order, since there's no guarantee

components/camera/transformpipeline/composed.go

+1-1
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ func (dtp *depthToPretty) Close(ctx context.Context) error {
8383
return dtp.src.Close(ctx)
8484
}
8585

86-
func (dtp *depthToPretty) PointCloud(ctx context.Context) (pointcloud.PointCloud, error) {
86+
func (dtp *depthToPretty) PointCloud(ctx context.Context, _ map[string]interface{}) (pointcloud.PointCloud, error) {
8787
ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::depthToPretty::PointCloud")
8888
defer span.End()
8989
if dtp.cameraModel == nil || dtp.cameraModel.PinholeCameraIntrinsics == nil {

components/camera/transformpipeline/pipeline.go

+1-1
Original file line numberDiff line numberDiff line change
@@ -148,7 +148,7 @@ func (tp transformPipeline) Read(ctx context.Context) (image.Image, func(), erro
148148
return camera.ReadImage(ctx, tp.src)
149149
}
150150

151-
func (tp transformPipeline) PointCloud(ctx context.Context, extra map[string]interface{}) (pointcloud.PointCloud, error) {
151+
func (tp transformPipeline) PointCloud(ctx context.Context, _ map[string]interface{}) (pointcloud.PointCloud, error) {
152152
ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::PointCloud")
153153
defer span.End()
154154
if lastElem, ok := tp.pipeline[len(tp.pipeline)-1].(camera.PointCloudSource); ok {

components/camera/transformpipeline/segmenter.go

+1-1
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ func (cfg *segmenterConfig) Validate(path string) ([]string, error) {
7070
}
7171

7272
// PointCloud function calls a segmenter service on the underlying camera and returns a pointcloud.
73-
func (ss *segmenterSource) PointCloud(ctx context.Context, extra map[string]interface{}) (pointcloud.PointCloud, error) {
73+
func (ss *segmenterSource) PointCloud(ctx context.Context, _ map[string]interface{}) (pointcloud.PointCloud, error) {
7474
ctx, span := trace.StartSpan(ctx, "camera::transformpipeline::segmenter::PointCloud")
7575
defer span.End()
7676

0 commit comments

Comments
 (0)