universalrobots

package
v0.2.7 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Dec 16, 2022 License: AGPL-3.0 Imports: 25 Imported by: 0

Documentation

Overview

Package universalrobots implements the UR arm from Universal Robots.

Index

Constants

View Source
const ModelName = "ur5e"

ModelName is the string used to refer to the ur5e arm model.

Variables

This section is empty.

Functions

func Model added in v0.1.3

func Model(name string) (referenceframe.Model, error)

Model returns the kinematics model of the ur arm, also has all Frame information.

func URArmConnect

func URArmConnect(ctx context.Context, r robot.Robot, cfg config.Component, logger golog.Logger) (arm.LocalArm, error)

URArmConnect TODO.

Types

type AttrConfig

type AttrConfig struct {
	Speed               float64 `json:"speed_degs_per_sec"`
	Host                string  `json:"host"`
	ArmHostedKinematics bool    `json:"arm_hosted_kinematics,omitempty"`
}

AttrConfig is used for converting config attributes.

func (*AttrConfig) Validate added in v0.2.0

func (cfg *AttrConfig) Validate(path string) ([]string, error)

Validate ensures all parts of the config are valid.

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.

func (CartesianInfo) SimpleString

func (c CartesianInfo) SimpleString() string

SimpleString TODO.

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.

func (JointData) AngleValues

func (j JointData) AngleValues() float64

AngleValues TODO.

type KinematicInfo

type KinematicInfo struct {
	Cheksum int32
	DHtheta float64
	DHa     float64
	Dhd     float64
	Dhalpha float64
}

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
	// 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

type URArm struct {
	generic.Unimplemented
	io.Closer
	// contains filtered or unexported fields
}

URArm TODO.

func (*URArm) AddToLog

func (ua *URArm) AddToLog(msg string) error

AddToLog TODO.

func (*URArm) Close

func (ua *URArm) Close(ctx context.Context) error

Close TODO.

func (*URArm) CurrentInputs

func (ua *URArm) CurrentInputs(ctx context.Context) ([]referenceframe.Input, error)

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) GoToInputs

func (ua *URArm) GoToInputs(ctx context.Context, goal []referenceframe.Input) error

GoToInputs TODO.

func (*URArm) IsMoving

func (ua *URArm) IsMoving(ctx context.Context) (bool, error)

IsMoving returns whether the arm is moving.

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

func (ua *URArm) MoveToJointPositionRadians(ctx context.Context, radians []float64) error

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,
	worldState *referenceframe.WorldState,
	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. If these are used with obstacles or interaction spaces embedded in the world state an error will be thrown, as the hosted planning does not support these constraints.

func (*URArm) State

func (ua *URArm) State() (RobotState, error)

State TODO.

func (*URArm) Stop

func (ua *URArm) Stop(ctx context.Context, extra map[string]interface{}) error

Stop stops the arm with some deceleration.

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL