Skip to content

Commit 3f1a3b6

Browse files
authored
[RSDK-7904] Remove status and streaming status from robot interface (#4461)
1 parent cd49068 commit 3f1a3b6

32 files changed

+89
-2061
lines changed

components/arm/arm.go

Lines changed: 0 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@ import (
1010
"context"
1111
"fmt"
1212

13-
v1 "go.viam.com/api/common/v1"
1413
pb "go.viam.com/api/component/arm/v1"
1514

1615
"go.viam.com/rdk/data"
@@ -24,7 +23,6 @@ import (
2423

2524
func init() {
2625
resource.RegisterAPI(API, resource.APIRegistration[Arm]{
27-
Status: resource.StatusFunc(CreateStatus),
2826
RPCServiceServerConstructor: NewRPCServiceServer,
2927
RPCServiceHandler: pb.RegisterArmServiceHandlerFromEndpoint,
3028
RPCServiceDesc: &pb.ArmService_ServiceDesc,
@@ -146,32 +144,6 @@ func NamesFromRobot(r robot.Robot) []string {
146144
return robot.NamesByAPI(r, API)
147145
}
148146

149-
// CreateStatus creates a status from the arm. This will report calculated end effector positions even if the given
150-
// arm is perceived to be out of bounds.
151-
func CreateStatus(ctx context.Context, a Arm) (*pb.Status, error) {
152-
model := a.ModelFrame()
153-
joints, err := a.JointPositions(ctx, nil)
154-
if err != nil {
155-
return nil, err
156-
}
157-
158-
var endPosition *v1.Pose
159-
if endPose, err := referenceframe.ComputeOOBPosition(model, joints); err == nil {
160-
endPosition = spatialmath.PoseToProtobuf(endPose)
161-
}
162-
163-
var jointPositions *pb.JointPositions
164-
if jp, err := referenceframe.JointPositionsFromInputs(model, joints); err == nil {
165-
jointPositions = jp
166-
}
167-
168-
isMoving, err := a.IsMoving(ctx)
169-
if err != nil {
170-
return nil, err
171-
}
172-
return &pb.Status{EndPosition: endPosition, JointPositions: jointPositions, IsMoving: isMoving}, nil
173-
}
174-
175147
// CheckDesiredJointPositions validates that the desired joint positions either bring the joint back
176148
// in bounds or do not move the joint more out of bounds.
177149
func CheckDesiredJointPositions(ctx context.Context, a Arm, desiredInputs []referenceframe.Input) error {

components/arm/arm_test.go

Lines changed: 0 additions & 166 deletions
Original file line numberDiff line numberDiff line change
@@ -2,18 +2,13 @@ package arm_test
22

33
import (
44
"context"
5-
"errors"
65
"testing"
76

8-
"github.com/go-viper/mapstructure/v2"
97
"github.com/golang/geo/r3"
10-
pb "go.viam.com/api/component/arm/v1"
118
"go.viam.com/test"
12-
"go.viam.com/utils/protoutils"
139

1410
"go.viam.com/rdk/components/arm"
1511
"go.viam.com/rdk/components/arm/fake"
16-
ur "go.viam.com/rdk/components/arm/universalrobots"
1712
"go.viam.com/rdk/components/generic"
1813
"go.viam.com/rdk/logging"
1914
"go.viam.com/rdk/referenceframe"
@@ -30,167 +25,6 @@ const (
3025
missingArmName = "arm4"
3126
)
3227

33-
var pose = spatialmath.NewPoseFromPoint(r3.Vector{X: 1, Y: 2, Z: 3})
34-
35-
func TestStatusValid(t *testing.T) {
36-
status := &pb.Status{
37-
EndPosition: spatialmath.PoseToProtobuf(pose),
38-
JointPositions: &pb.JointPositions{Values: []float64{1.1, 2.2, 3.3}},
39-
IsMoving: true,
40-
}
41-
newStruct, err := protoutils.StructToStructPb(status)
42-
test.That(t, err, test.ShouldBeNil)
43-
test.That(
44-
t,
45-
newStruct.AsMap(),
46-
test.ShouldResemble,
47-
map[string]interface{}{
48-
"end_position": map[string]interface{}{"o_z": 1.0, "x": 1.0, "y": 2.0, "z": 3.0},
49-
"joint_positions": map[string]interface{}{"values": []interface{}{1.1, 2.2, 3.3}},
50-
"is_moving": true,
51-
},
52-
)
53-
54-
convMap := &pb.Status{}
55-
decoder, err := mapstructure.NewDecoder(&mapstructure.DecoderConfig{TagName: "json", Result: &convMap})
56-
test.That(t, err, test.ShouldBeNil)
57-
err = decoder.Decode(newStruct.AsMap())
58-
test.That(t, err, test.ShouldBeNil)
59-
test.That(t, convMap, test.ShouldResemble, status)
60-
}
61-
62-
func TestCreateStatus(t *testing.T) {
63-
successfulPose := spatialmath.NewPose(
64-
r3.Vector{-802.801508917897990613710135, -248.284077946287368376943050, 9.115758604150467903082244},
65-
&spatialmath.R4AA{1.5810814917942602, 0.992515011486776, -0.0953988491934626, 0.07624310818669232},
66-
)
67-
successfulStatus := &pb.Status{
68-
EndPosition: spatialmath.PoseToProtobuf(successfulPose),
69-
JointPositions: &pb.JointPositions{Values: []float64{1.1, 2.2, 3.3, 1.1, 2.2, 3.3}},
70-
IsMoving: true,
71-
}
72-
73-
injectArm := &inject.Arm{}
74-
75-
//nolint:unparam
76-
successfulJointPositionsFunc := func(context.Context, map[string]interface{}) ([]referenceframe.Input, error) {
77-
return referenceframe.FloatsToInputs(referenceframe.JointPositionsToRadians(successfulStatus.JointPositions)), nil
78-
}
79-
80-
successfulIsMovingFunc := func(context.Context) (bool, error) {
81-
return true, nil
82-
}
83-
84-
successfulModelFrameFunc := func() referenceframe.Model {
85-
model, _ := ur.MakeModelFrame("ur5e")
86-
return model
87-
}
88-
89-
t.Run("working", func(t *testing.T) {
90-
injectArm.JointPositionsFunc = successfulJointPositionsFunc
91-
injectArm.IsMovingFunc = successfulIsMovingFunc
92-
injectArm.ModelFrameFunc = successfulModelFrameFunc
93-
94-
expectedPose := successfulPose
95-
expectedStatus := successfulStatus
96-
97-
actualStatus, err := arm.CreateStatus(context.Background(), injectArm)
98-
test.That(t, err, test.ShouldBeNil)
99-
test.That(t, actualStatus.IsMoving, test.ShouldEqual, expectedStatus.IsMoving)
100-
test.That(t, actualStatus.JointPositions, test.ShouldResemble, expectedStatus.JointPositions)
101-
102-
actualPose := spatialmath.NewPoseFromProtobuf(actualStatus.EndPosition)
103-
test.That(t, spatialmath.PoseAlmostEqualEps(actualPose, expectedPose, 0.01), test.ShouldBeTrue)
104-
105-
resourceAPI, ok, err := resource.LookupAPIRegistration[arm.Arm](arm.API)
106-
test.That(t, err, test.ShouldBeNil)
107-
test.That(t, ok, test.ShouldBeTrue)
108-
statusInterface, err := resourceAPI.Status(context.Background(), injectArm)
109-
test.That(t, err, test.ShouldBeNil)
110-
111-
statusMap, err := protoutils.InterfaceToMap(statusInterface)
112-
test.That(t, err, test.ShouldBeNil)
113-
114-
endPosMap, err := protoutils.InterfaceToMap(statusMap["end_position"])
115-
test.That(t, err, test.ShouldBeNil)
116-
actualPose = spatialmath.NewPose(
117-
r3.Vector{endPosMap["x"].(float64), endPosMap["y"].(float64), endPosMap["z"].(float64)},
118-
&spatialmath.OrientationVectorDegrees{
119-
endPosMap["theta"].(float64), endPosMap["o_x"].(float64),
120-
endPosMap["o_y"].(float64), endPosMap["o_z"].(float64),
121-
},
122-
)
123-
test.That(t, spatialmath.PoseAlmostEqualEps(actualPose, expectedPose, 0.01), test.ShouldBeTrue)
124-
125-
moving := statusMap["is_moving"].(bool)
126-
test.That(t, moving, test.ShouldEqual, expectedStatus.IsMoving)
127-
128-
jPosFace := statusMap["joint_positions"].(map[string]interface{})["values"].([]interface{})
129-
actualJointPositions := []float64{
130-
jPosFace[0].(float64), jPosFace[1].(float64), jPosFace[2].(float64),
131-
jPosFace[3].(float64), jPosFace[4].(float64), jPosFace[5].(float64),
132-
}
133-
test.That(t, actualJointPositions, test.ShouldResemble, expectedStatus.JointPositions.Values)
134-
})
135-
136-
t.Run("not moving", func(t *testing.T) {
137-
injectArm.JointPositionsFunc = successfulJointPositionsFunc
138-
injectArm.ModelFrameFunc = successfulModelFrameFunc
139-
140-
injectArm.IsMovingFunc = func(context.Context) (bool, error) {
141-
return false, nil
142-
}
143-
144-
expectedPose := successfulPose
145-
expectedStatus := &pb.Status{
146-
EndPosition: successfulStatus.EndPosition, //nolint:govet
147-
JointPositions: successfulStatus.JointPositions,
148-
IsMoving: false,
149-
}
150-
151-
actualStatus, err := arm.CreateStatus(context.Background(), injectArm)
152-
test.That(t, err, test.ShouldBeNil)
153-
test.That(t, actualStatus.IsMoving, test.ShouldEqual, expectedStatus.IsMoving)
154-
test.That(t, actualStatus.JointPositions, test.ShouldResemble, expectedStatus.JointPositions)
155-
actualPose := spatialmath.NewPoseFromProtobuf(actualStatus.EndPosition)
156-
test.That(t, spatialmath.PoseAlmostEqualEps(actualPose, expectedPose, 0.01), test.ShouldBeTrue)
157-
})
158-
159-
t.Run("fail on JointPositions", func(t *testing.T) {
160-
injectArm.IsMovingFunc = successfulIsMovingFunc
161-
injectArm.ModelFrameFunc = successfulModelFrameFunc
162-
163-
errFail := errors.New("can't get joint positions")
164-
injectArm.JointPositionsFunc = func(ctx context.Context, extra map[string]interface{}) ([]referenceframe.Input, error) {
165-
return nil, errFail
166-
}
167-
168-
actualStatus, err := arm.CreateStatus(context.Background(), injectArm)
169-
test.That(t, err, test.ShouldBeError, errFail)
170-
test.That(t, actualStatus, test.ShouldBeNil)
171-
})
172-
173-
t.Run("nil model frame", func(t *testing.T) {
174-
injectArm.IsMovingFunc = successfulIsMovingFunc
175-
injectArm.JointPositionsFunc = successfulJointPositionsFunc
176-
injectArm.ModelFrameFunc = func() referenceframe.Model {
177-
return nil
178-
}
179-
180-
expectedStatus := &pb.Status{
181-
EndPosition: nil,
182-
JointPositions: successfulStatus.JointPositions,
183-
IsMoving: successfulStatus.IsMoving,
184-
}
185-
186-
actualStatus, err := arm.CreateStatus(context.Background(), injectArm)
187-
test.That(t, err, test.ShouldBeNil)
188-
test.That(t, actualStatus.EndPosition, test.ShouldEqual, expectedStatus.EndPosition)
189-
test.That(t, actualStatus.JointPositions, test.ShouldResemble, expectedStatus.JointPositions)
190-
test.That(t, actualStatus.IsMoving, test.ShouldEqual, expectedStatus.IsMoving)
191-
})
192-
}
193-
19428
func TestXArm6Locations(t *testing.T) {
19529
// check the exact values/locations of arm geometries at a couple different poses
19630
logger := logging.NewTestLogger(t)

components/base/base.go

Lines changed: 0 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,6 @@ import (
88
"context"
99

1010
"github.com/golang/geo/r3"
11-
commonpb "go.viam.com/api/common/v1"
1211
pb "go.viam.com/api/component/base/v1"
1312

1413
"go.viam.com/rdk/resource"
@@ -17,7 +16,6 @@ import (
1716

1817
func init() {
1918
resource.RegisterAPI(API, resource.APIRegistration[Base]{
20-
Status: resource.StatusFunc(CreateStatus),
2119
RPCServiceServerConstructor: NewRPCServiceServer,
2220
RPCServiceHandler: pb.RegisterBaseServiceHandlerFromEndpoint,
2321
RPCServiceDesc: &pb.BaseService_ServiceDesc,
@@ -144,12 +142,3 @@ func FromRobot(r robot.Robot, name string) (Base, error) {
144142
func NamesFromRobot(r robot.Robot) []string {
145143
return robot.NamesByAPI(r, API)
146144
}
147-
148-
// CreateStatus creates a status from the base.
149-
func CreateStatus(ctx context.Context, b Base) (*commonpb.ActuatorStatus, error) {
150-
isMoving, err := b.IsMoving(ctx)
151-
if err != nil {
152-
return nil, err
153-
}
154-
return &commonpb.ActuatorStatus{IsMoving: isMoving}, nil
155-
}

components/base/base_test.go

Lines changed: 0 additions & 64 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,9 @@
11
package base_test
22

33
import (
4-
"context"
54
"testing"
65

7-
"github.com/go-viper/mapstructure/v2"
8-
commonpb "go.viam.com/api/common/v1"
96
"go.viam.com/test"
10-
"go.viam.com/utils/protoutils"
117

128
"go.viam.com/rdk/components/base"
139
"go.viam.com/rdk/components/generic"
@@ -21,66 +17,6 @@ const (
2117
failBaseName = "base2"
2218
)
2319

24-
func TestStatusValid(t *testing.T) {
25-
status := &commonpb.ActuatorStatus{
26-
IsMoving: true,
27-
}
28-
newStruct, err := protoutils.StructToStructPb(status)
29-
test.That(t, err, test.ShouldBeNil)
30-
test.That(
31-
t,
32-
newStruct.AsMap(),
33-
test.ShouldResemble,
34-
map[string]interface{}{
35-
"is_moving": true,
36-
},
37-
)
38-
39-
convMap := &commonpb.ActuatorStatus{}
40-
decoder, err := mapstructure.NewDecoder(&mapstructure.DecoderConfig{TagName: "json", Result: &convMap})
41-
test.That(t, err, test.ShouldBeNil)
42-
err = decoder.Decode(newStruct.AsMap())
43-
test.That(t, err, test.ShouldBeNil)
44-
test.That(t, convMap, test.ShouldResemble, status)
45-
}
46-
47-
func TestCreateStatus(t *testing.T) {
48-
t.Run("is moving", func(t *testing.T) {
49-
status := &commonpb.ActuatorStatus{
50-
IsMoving: true,
51-
}
52-
53-
injectBase := &inject.Base{}
54-
injectBase.IsMovingFunc = func(context.Context) (bool, error) {
55-
return true, nil
56-
}
57-
status1, err := base.CreateStatus(context.Background(), injectBase)
58-
test.That(t, err, test.ShouldBeNil)
59-
test.That(t, status1, test.ShouldResemble, status)
60-
61-
resourceAPI, ok, err := resource.LookupAPIRegistration[base.Base](base.API)
62-
test.That(t, err, test.ShouldBeNil)
63-
test.That(t, ok, test.ShouldBeTrue)
64-
status2, err := resourceAPI.Status(context.Background(), injectBase)
65-
test.That(t, err, test.ShouldBeNil)
66-
test.That(t, status2, test.ShouldResemble, status)
67-
})
68-
69-
t.Run("is not moving", func(t *testing.T) {
70-
status := &commonpb.ActuatorStatus{
71-
IsMoving: false,
72-
}
73-
74-
injectBase := &inject.Base{}
75-
injectBase.IsMovingFunc = func(context.Context) (bool, error) {
76-
return false, nil
77-
}
78-
status1, err := base.CreateStatus(context.Background(), injectBase)
79-
test.That(t, err, test.ShouldBeNil)
80-
test.That(t, status1, test.ShouldResemble, status)
81-
})
82-
}
83-
8420
func TestFromRobot(t *testing.T) {
8521
r := &inject.Robot{}
8622
rs := map[resource.Name]resource.Resource{

components/board/board.go

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@ import (
2020

2121
func init() {
2222
resource.RegisterAPI(API, resource.APIRegistration[Board]{
23-
Status: resource.StatusFunc(CreateStatus),
2423
RPCServiceServerConstructor: NewRPCServiceServer,
2524
RPCServiceHandler: pb.RegisterBoardServiceHandlerFromEndpoint,
2625
RPCServiceDesc: &pb.BoardService_ServiceDesc,

0 commit comments

Comments
 (0)