Documentation
¶
Overview ¶
Package arm defines the arm that a robot uses to manipulate objects. For more information, see the arm component docs.
Package arm contains a gRPC based arm client.
Package arm contains a gRPC based arm service server.
Index ¶
- Constants
- Variables
- func CheckDesiredJointPositions(ctx context.Context, a Arm, desiredInputs []referenceframe.Input) error
- func Named(name string) resource.Name
- func NamesFromRobot(r robot.Robot) []string
- func NewRPCServiceServer(coll resource.APIResourceGetter[Arm], logger logging.Logger) interface{}
- type Arm
- func FromDependencies(deps resource.Dependencies, name string) (Arm, error)deprecated
- func FromProvider(provider resource.Provider, name string) (Arm, error)
- func FromRobot(r robot.Robot, name string) (Arm, error)deprecated
- func NewClientFromConn(ctx context.Context, conn rpc.ClientConn, remoteName string, ...) (Arm, error)
- type MoveOptions
Constants ¶
const SubtypeName = "arm"
SubtypeName is a constant that identifies the component resource API string "arm".
Variables ¶
var API = resource.APINamespaceRDK.WithComponentType(SubtypeName)
API is a variable that identifies the component resource API.
Functions ¶
func CheckDesiredJointPositions ¶ added in v0.2.15
func CheckDesiredJointPositions(ctx context.Context, a Arm, desiredInputs []referenceframe.Input) error
CheckDesiredJointPositions validates that the desired joint positions either bring the joint back in bounds or do not move the joint more out of bounds.
func NamesFromRobot ¶
NamesFromRobot is a helper for getting all arm names from the given Robot.
func NewRPCServiceServer ¶ added in v0.2.36
func NewRPCServiceServer(coll resource.APIResourceGetter[Arm], logger logging.Logger) interface{}
NewRPCServiceServer constructs an arm gRPC service server. It is intentionally untyped to prevent use outside of tests.
Types ¶
type Arm ¶
type Arm interface {
resource.Resource
resource.Shaped
resource.Actuator
framesystem.InputEnabled
// EndPosition returns the current position of the arm.
EndPosition(ctx context.Context, extra map[string]interface{}) (spatialmath.Pose, error)
// MoveToPosition moves the arm to the given absolute position.
// This will block until done or a new operation cancels this one.
MoveToPosition(ctx context.Context, pose spatialmath.Pose, extra map[string]interface{}) error
// MoveToJointPositions moves the arm's joints to the given positions.
// This will block until done or a new operation cancels this one.
MoveToJointPositions(ctx context.Context, positions []referenceframe.Input, extra map[string]interface{}) error
// MoveThroughJointPositions moves the arm's joints through the given positions in the order they are specified.
// This will block until done or a new operation cancels this one.
MoveThroughJointPositions(ctx context.Context, positions [][]referenceframe.Input, options *MoveOptions, extra map[string]any) error
// JointPositions returns the current joint positions of the arm.
JointPositions(ctx context.Context, extra map[string]interface{}) ([]referenceframe.Input, error)
// Get3DModels returns the 3D models of the arm.
Get3DModels(ctx context.Context, extra map[string]interface{}) (map[string]*commonpb.Mesh, error)
}
An Arm represents a physical robotic arm that exists in three-dimensional space. For more information, see the arm component docs.
EndPosition example:
myArm, err := arm.FromProvider(machine, "my_arm") // Get the end position of the arm as a Pose. pos, err := myArm.EndPosition(context.Background(), nil)
For more information, see the EndPosition method docs.
MoveToPosition example:
myArm, err := arm.FromProvider(machine, "my_arm")
// Create a Pose for the arm.
examplePose := spatialmath.NewPose(
r3.Vector{X: 5, Y: 5, Z: 5},
&spatialmath.OrientationVectorDegrees{OX: 5, OY: 5, Theta: 20},
)
// Move your arm to the Pose.
err = myArm.MoveToPosition(context.Background(), examplePose, nil)
For more information, see the MoveToPosition method docs.
MoveToJointPositions example:
myArm, err := arm.FromProvider(machine, "my_arm")
// Declare an array of values with your desired rotational value (in radians) for each joint on the arm.
inputs := referenceframe.FloatsToInputs([]float64{0, math.Pi/2, math.Pi})
// Move each joint of the arm to the positions specified in the above slice
err = myArm.MoveToJointPositions(context.Background(), inputs, nil)
For more information, see the MoveToJointPositions method docs.
MoveThroughJointPositions example:
myArm, err := arm.FromProvider(machine, "my_arm")
// Declare a 2D array of values with your desired rotational value (in radians) for each joint on the arm.
inputs := [][]referenceframe.Input{
referenceframe.FloatsToInputs([]float64{0, math.Pi/2, math.Pi})
referenceframe.FloatsToInputs([]float64{0, 0, 0})
}
// Move each joint of the arm through the positions in the slice defined above
err = myArm.MoveThroughJointPositions(context.Background(), inputs, nil, nil)
For more information, see the MoveThroughJointPositions method docs.
JointPositions example:
myArm, err := arm.FromProvider(machine, "my_arm") // Get the current position of each joint on the arm as JointPositions. pos, err := myArm.JointPositions(context.Background(), nil)
For more information, see the JointPositions method docs.
func FromDependencies
deprecated
func FromDependencies(deps resource.Dependencies, name string) (Arm, error)
Deprecated: FromDependencies is a helper for getting the named arm from a collection of dependencies. Use FromProvider instead.
func FromProvider ¶ added in v0.98.0
FromProvider is a helper for getting the named arm from a resource Provider (collection of Dependencies or a Robot).
type MoveOptions ¶ added in v0.50.0
type MoveOptions struct {
MaxVelRads, MaxAccRads float64
}
MoveOptions define parameters to be obeyed during arm movement.
Directories
¶
| Path | Synopsis |
|---|---|
|
Package fake implements a fake arm.
|
Package fake implements a fake arm. |
|
3d_models
Package models3d contains embedded 3D model files and related mappings for fake arm models.
|
Package models3d contains embedded 3D model files and related mappings for fake arm models. |
|
Package register registers all relevant arms
|
Package register registers all relevant arms |
|
Package sim implements the arm API and simulates moving to joint positions over time.
|
Package sim implements the arm API and simulates moving to joint positions over time. |
|
Package wrapper is a package that defines an implementation that wraps a partially implemented arm
|
Package wrapper is a package that defines an implementation that wraps a partially implemented arm |