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 CreateStatus(ctx context.Context, a Arm) (*pb.Status, error)
- func GoToWaypoints(ctx context.Context, a Arm, waypoints [][]referenceframe.Input) error
- func Named(name string) resource.Name
- func NamesFromRobot(r robot.Robot) []string
- func NewRPCServiceServer(coll resource.APIResourceCollection[Arm]) interface{}
- type Arm
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 CreateStatus ¶
CreateStatus creates a status from the arm. This will report calculated end effector positions even if the given arm is perceived to be out of bounds.
func GoToWaypoints ¶
GoToWaypoints will visit in turn each of the joint position waypoints generated by a motion planner.
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.APIResourceCollection[Arm]) 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 referenceframe.ModelFramer 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, positionDegs *pb.JointPositions, extra map[string]interface{}) error // JointPositions returns the current joint positions of the arm. JointPositions(ctx context.Context, extra map[string]interface{}) (*pb.JointPositions, 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.FromRobot(machine, "my_arm") // Get the end position of the arm as a Pose. pos, err := myArm.EndPosition(context.Background(), nil)
MoveToPosition example:
myArm, err := arm.FromRobot(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)
MoveToJointPositions example:
// Assumes you have imported "go.viam.com/api/component/arm/v1" as `componentpb` myArm, err := arm.FromRobot(machine, "my_arm") // Declare an array of values with your desired rotational value for each joint on the arm. degrees := []float64{4.0, 5.0, 6.0} // Declare a new JointPositions with these values. jointPos := &componentpb.JointPositions{Values: degrees} // Move each joint of the arm to the position these values specify. err = myArm.MoveToJointPositions(context.Background(), jointPos, nil)
JointPositions example:
myArm , err := arm.FromRobot(machine, "my_arm") // Get the current position of each joint on the arm as JointPositions. pos, err := myArm.JointPositions(context.Background(), nil)
func FromDependencies ¶
func FromDependencies(deps resource.Dependencies, name string) (Arm, error)
FromDependencies is a helper for getting the named arm from a collection of dependencies.
Directories ¶
Path | Synopsis |
---|---|
Package eva implements the Eva robot from Automata.
|
Package eva implements the Eva robot from Automata. |
Package fake implements a fake arm.
|
Package fake implements a fake arm. |
Package register registers all relevant arms
|
Package register registers all relevant arms |
Package universalrobots implements the UR arm from Universal Robots.
|
Package universalrobots implements the UR arm from Universal Robots. |
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 |
Package xarm implements some UFactory arms (xArm 6, xArm 7, and Lite 6).
|
Package xarm implements some UFactory arms (xArm 6, xArm 7, and Lite 6). |