Documentation ¶
Overview ¶
Package universalrobots implements the UR arm from Universal Robots.
Index ¶
- Variables
- func MakeModelFrame(name string) (referenceframe.Model, error)
- func URArmConnect(ctx context.Context, conf resource.Config, logger golog.Logger) (arm.Arm, error)
- type AdditionalInfo
- type CartesianInfo
- type Config
- type ForceModeData
- type JointData
- type KinematicInfo
- type MasterboardData
- type RobotModeData
- type RobotState
- type ToolData
- type URArm
- func (ua *URArm) AddToLog(msg string) error
- func (ua *URArm) Close(ctx context.Context) error
- func (ua *URArm) CurrentInputs(ctx context.Context) ([]referenceframe.Input, error)
- func (ua *URArm) EndPosition(ctx context.Context, extra map[string]interface{}) (spatialmath.Pose, error)
- func (ua *URArm) Geometries(ctx context.Context) ([]spatialmath.Geometry, error)
- func (ua *URArm) GoToInputs(ctx context.Context, goal []referenceframe.Input) error
- func (ua *URArm) IsMoving(ctx context.Context) (bool, error)
- func (ua *URArm) JointPositions(ctx context.Context, extra map[string]interface{}) (*pb.JointPositions, error)
- func (ua *URArm) ModelFrame() referenceframe.Model
- func (ua *URArm) MoveToJointPositionRadians(ctx context.Context, radians []float64) error
- func (ua *URArm) MoveToJointPositions(ctx context.Context, joints *pb.JointPositions, extra map[string]interface{}) error
- func (ua *URArm) MoveToPosition(ctx context.Context, pos spatialmath.Pose, extra map[string]interface{}) error
- func (ua *URArm) Reconfigure(ctx context.Context, deps resource.Dependencies, conf resource.Config) error
- func (ua *URArm) State() (RobotState, error)
- func (ua *URArm) Stop(ctx context.Context, extra map[string]interface{}) error
Constants ¶
This section is empty.
Variables ¶
var Model = resource.DefaultModelFamily.WithModel("ur5e")
Model is the name of the UR5e model of an arm component.
Functions ¶
func MakeModelFrame ¶ added in v0.2.36
func MakeModelFrame(name string) (referenceframe.Model, error)
MakeModelFrame returns the kinematics model of the ur arm, also has all Frame information.
Types ¶
type AdditionalInfo ¶ added in v0.2.10
type AdditionalInfo struct { TpButtonState byte FreedriveButtonEnabled bool IOEnabledFreedrive bool Reserved byte }
AdditionalInfo additional info from ur arm.
type CartesianInfo ¶
type CartesianInfo struct { X float64 Y float64 Z float64 Rx float64 Ry float64 Rz float64 TCPOffsetX float64 TCPOffsetY float64 TCPOffsetZ float64 TCPOffsetRx float64 TCPOffsetRy float64 TCPOffsetRz float64 }
CartesianInfo TODO.
func (CartesianInfo) NondelimitedString ¶
func (c CartesianInfo) NondelimitedString() string
NondelimitedString TODO.
type Config ¶ added in v0.2.36
type Config struct { Speed float64 `json:"speed_degs_per_sec"` Host string `json:"host"` ArmHostedKinematics bool `json:"arm_hosted_kinematics,omitempty"` }
Config is used for converting config attributes.
type ForceModeData ¶
type ForceModeData struct { Fx float64 Fy float64 Fz float64 Frx float64 Fry float64 Frz float64 RobotDexterity float64 }
ForceModeData TODO.
type JointData ¶
type JointData struct { Qactual float64 // angle currently in radians Qtarget float64 // angle target in radians QDactual float64 Iactual float32 Vactual float32 Tmotor float32 Tmicro float32 JointMode byte }
JointData TODO.
type KinematicInfo ¶
KinematicInfo TODO.
type MasterboardData ¶
type MasterboardData struct { DigitalInputBits int32 DigitalOutputBits int32 AnalogInputRange0 byte AnalogInputRange1 byte AnalogInput0 float64 AnalogInput1 float64 AnalogOutputDomain0 byte AnalogOutputDomain1 byte AnalogOutput0 float64 AnalogOutput1 float64 MasterBoardTemperature float32 RobotVoltage48V float32 RobotCurrent float32 MasterIOCurrent float32 SafetyMode byte InReducedMode byte Euromap67InterfaceInstalled byte NotUsed1 uint32 OperationalModeSelectorInput byte ThreePositionEnablingDeviceInput byte NotUsed2 byte }
MasterboardData TODO.
type RobotModeData ¶
type RobotModeData struct { Timestamp uint64 IsRealRobotConnected bool IsRealRobotEnabled bool IsRobotPowerOn bool IsEmergencyStopped bool IsProtectiveStopped bool IsProgramRunning bool IsProgramPaused bool RobotMode byte ControlMode byte TargetSpeedFraction float64 SpeedScaling float64 TargetSpeedFractionLimit float64 }
RobotModeData TODO.
type RobotState ¶
type RobotState struct { RobotModeData Joints []JointData ToolData MasterboardData CartesianInfo Kinematics []KinematicInfo ForceModeData AdditionalInfo // contains filtered or unexported fields }
RobotState TODO.
type ToolData ¶
type ToolData struct { AnalogInputRange0 byte AnalogInputRange1 byte AnalogInput0 float64 AnalogInput1 float64 ToolVoltage48V float32 ToolOutputVoltage byte ToolCurrent float32 ToolTemperature float32 ToolMode byte }
ToolData TODO.
type URArm ¶
URArm TODO.
func (*URArm) CurrentInputs ¶
CurrentInputs TODO.
func (*URArm) EndPosition ¶
func (ua *URArm) EndPosition(ctx context.Context, extra map[string]interface{}) (spatialmath.Pose, error)
EndPosition computes and returns the current cartesian position.
func (*URArm) Geometries ¶ added in v0.2.50
Geometries returns the list of geometries associated with the resource, in any order. The poses of the geometries reflect their current location relative to the frame of the resource.
func (*URArm) GoToInputs ¶
GoToInputs TODO.
func (*URArm) JointPositions ¶
func (ua *URArm) JointPositions(ctx context.Context, extra map[string]interface{}) (*pb.JointPositions, error)
JointPositions TODO.
func (*URArm) ModelFrame ¶
func (ua *URArm) ModelFrame() referenceframe.Model
ModelFrame returns all the information necessary for including the arm in a FrameSystem.
func (*URArm) MoveToJointPositionRadians ¶
MoveToJointPositionRadians TODO.
func (*URArm) MoveToJointPositions ¶
func (ua *URArm) MoveToJointPositions(ctx context.Context, joints *pb.JointPositions, extra map[string]interface{}) error
MoveToJointPositions TODO.
func (*URArm) MoveToPosition ¶
func (ua *URArm) MoveToPosition(ctx context.Context, pos spatialmath.Pose, extra map[string]interface{}) error
MoveToPosition moves the arm to the specified cartesian position. If the UR arm was configured with "arm_hosted_kinematics = 'true'" or extra["arm_hosted_kinematics"] = true is specified at runtime this command will use the kinematics hosted by the Universal Robots arm.
func (*URArm) Reconfigure ¶ added in v0.2.36
func (ua *URArm) Reconfigure(ctx context.Context, deps resource.Dependencies, conf resource.Config) error
Reconfigure atomically reconfigures this arm in place based on the new config.