Documentation ¶
Overview ¶
Package referenceframe defines the api and does the math of translating between reference frames Useful for if you have a camera, connected to a gripper, connected to an arm, and need to translate the camera reference frame to the arm reference frame, if you've found something in the camera, and want to move the gripper + arm to get it.
Index ¶
- Constants
- Variables
- func FrameSystemGeometries(fs FrameSystem, inputMap map[string][]Input) (map[string]*GeometriesInFrame, error)
- func FrameSystemToPCD(system FrameSystem, inputs map[string][]Input, logger logging.Logger) (map[string][]r3.Vector, error)
- func GenerateRandomConfiguration(m Model, randSeed *rand.Rand) []float64
- func GeometriesInFrameToProtobuf(framedGeometries *GeometriesInFrame) *commonpb.GeometriesInFrame
- func InputsL2Distance(from, to []Input) float64
- func InputsToFloats(inputs []Input) []float64
- func JointPositionsFromRadians(radians []float64) *pb.JointPositions
- func JointPositionsToRadians(jp *pb.JointPositions) []float64
- func LinkInFrameToTransformProtobuf(framedLink *LinkInFrame) (*commonpb.Transform, error)
- func LinkInFramesToTransformsProtobuf(linkSlice []*LinkInFrame) ([]*commonpb.Transform, error)
- func NewDuplicateGeometryNameError(name string) error
- func NewFrameAlreadyExistsError(frameName string) error
- func NewFrameMissingError(frameName string) error
- func NewFrameNotInListOfTransformsError(frameName string) error
- func NewIncorrectInputLengthError(actual, expected int) error
- func NewParentFrameMissingError(partName, parentName string) error
- func NewParentFrameNilError(frameName string) error
- func NewParentFrameNotInMapOfParentsError(parentFrameName string) error
- func NewReservedWordError(configType, reservedWord string) error
- func NewUnsupportedJointTypeError(jointType string) error
- func PoseInFrameToProtobuf(framedPose *PoseInFrame) *commonpb.PoseInFrame
- func StartPositions(fs FrameSystem) map[string][]Input
- type DHParamConfig
- type Frame
- func NewNamedFrame(frame Frame, name string) Frame
- func NewRotationalFrame(name string, axis spatial.R4AA, limit Limit) (Frame, error)
- func NewStaticFrame(name string, pose spatial.Pose) (Frame, error)
- func NewStaticFrameWithGeometry(name string, pose spatial.Pose, geometry spatial.Geometry) (Frame, error)
- func NewTranslationalFrame(name string, axis r3.Vector, limit Limit) (Frame, error)
- func NewTranslationalFrameWithGeometry(name string, axis r3.Vector, limit Limit, geometry spatial.Geometry) (Frame, error)
- func NewZeroStaticFrame(name string) Frame
- type FrameSystem
- type FrameSystemPart
- type GeometriesInFrame
- type Input
- func FloatsToInputs(floats []float64) []Input
- func GetFrameInputs(frame Frame, inputMap map[string][]Input) ([]Input, error)
- func InterpolateInputs(from, to []Input, by float64) []Input
- func RandomFrameInputs(m Frame, rSeed *rand.Rand) []Input
- func RestrictedRandomFrameInputs(m Frame, rSeed *rand.Rand, restrictionPercent float64, reference []Input) ([]Input, error)
- type InputEnabled
- type JointConfig
- type Limit
- type LinkConfig
- type LinkInFrame
- type Model
- func ModelFromPath(modelPath, name string) (Model, error)
- func New2DMobileModelFrame(name string, limits []Limit, collisionGeometry spatialmath.Geometry) (Model, error)
- func ParseModelJSONFile(filename, modelName string) (Model, error)
- func ParseURDFFile(filename, modelName string) (Model, error)
- func UnmarshalModelJSON(jsonData []byte, modelName string) (Model, error)
- type ModelConfig
- type ModelFramer
- type PoseInFrame
- type SimpleModel
- func (m *SimpleModel) CachedTransform(inputs []Input) (spatialmath.Pose, error)
- func (m *SimpleModel) DoF() []Limit
- func (m *SimpleModel) Geometries(inputs []Input) (*GeometriesInFrame, error)
- func (m *SimpleModel) InputFromProtobuf(jp *pb.JointPositions) []Input
- func (m *SimpleModel) MarshalJSON() ([]byte, error)
- func (m *SimpleModel) ModelConfig() *ModelConfig
- func (bf SimpleModel) Name() string
- func (m *SimpleModel) ProtobufFromInput(input []Input) *pb.JointPositions
- func (m *SimpleModel) Transform(inputs []Input) (spatialmath.Pose, error)
- type Transformable
- type URDFConfig
- type URDFJoint
- type URDFLink
- type WorldState
- func (ws *WorldState) ObstacleNames() map[string]bool
- func (ws *WorldState) ObstaclesInWorldFrame(fs FrameSystem, inputs map[string][]Input) (*GeometriesInFrame, error)
- func (ws *WorldState) String() string
- func (ws *WorldState) ToProtobuf() (*commonpb.WorldState, error)
- func (ws *WorldState) Transforms() []*LinkInFrame
Constants ¶
const ( FixedJoint = "fixed" ContinuousJoint = "continuous" PrismaticJoint = "prismatic" RevoluteJoint = "revolute" )
The following are joint types we treat as constants.
const OOBErrString = "input out of bounds"
OOBErrString is a string that all OOB errors should contain, so that they can be checked for distinct from other Transform errors.
const World = "world"
World is the string "world", but made into an exported constant.
Variables ¶
var ErrAtLeastOneEndEffector = errors.New("need at least one end effector")
ErrAtLeastOneEndEffector is an error indicating that at least one end effector is required.
var ErrCircularReference = errors.New("infinite loop finding path from end effector to world")
ErrCircularReference is an error indicating that a circular path exists somewhere between the end effector and the world.
var ErrEmptyStringFrameName = errors.New("frame with name \"\" cannot be used")
ErrEmptyStringFrameName denotes an error when a frame with a name "" is specified.
var ErrMarshalingHighDOFFrame = errors.New("cannot marshal frame with >1 DOF, use a Model instead")
ErrMarshalingHighDOFFrame describes the error when attempting to marshal a frame with multiple degrees of freedom.
var ErrNilJointPositions = errors.New("joint positions are nil, check that you are" +
" passing non-empty joint positions when writing your driver")
ErrNilJointPositions denotes an error when the joint positions are nil.
var ErrNilModelFrame = errors.New("the model frame is nil, check that you are passing non-empty kinematics when writing your driver")
ErrNilModelFrame denotes an error when the kinematics in form of model frames are nil.
var ErrNilPose = errors.New("pose was nil")
ErrNilPose denotes an error when a pose is nil.
var ErrNilPoseInFrame = errors.New("pose in frame was nil")
ErrNilPoseInFrame denotes an error when a pose in frame is nil.
var ErrNoModelInformation = errors.New("no model information")
ErrNoModelInformation is used when there is no model information.
var ErrNoWorldConnection = errors.New("there are no robot parts that connect to a 'world' node. Root node must be named 'world'")
ErrNoWorldConnection describes the error when a frame system is built but nothing is connected to the world node.
Functions ¶
func FrameSystemGeometries ¶ added in v0.2.15
func FrameSystemGeometries(fs FrameSystem, inputMap map[string][]Input) (map[string]*GeometriesInFrame, error)
FrameSystemGeometries takes in a framesystem and returns a map where all elements are GeometriesInFrames with a World reference frame.
func FrameSystemToPCD ¶ added in v0.2.15
func FrameSystemToPCD(system FrameSystem, inputs map[string][]Input, logger logging.Logger) (map[string][]r3.Vector, error)
FrameSystemToPCD takes in a framesystem and returns a map where all elements are the point representation of their geometry type with respect to the world.
func GenerateRandomConfiguration ¶
GenerateRandomConfiguration generates a list of radian joint positions that are random but valid for each joint.
func GeometriesInFrameToProtobuf ¶
func GeometriesInFrameToProtobuf(framedGeometries *GeometriesInFrame) *commonpb.GeometriesInFrame
GeometriesInFrameToProtobuf converts a GeometriesInFrame struct to a GeometriesInFrame message as specified in common.proto.
func InputsL2Distance ¶ added in v0.2.34
InputsL2Distance returns the square of the two-norm between the from and to vectors.
func InputsToFloats ¶
InputsToFloats unwraps Inputs to raw floats.
func JointPositionsFromRadians ¶
func JointPositionsFromRadians(radians []float64) *pb.JointPositions
JointPositionsFromRadians converts the given slice of radians into joint positions (represented in degrees).
func JointPositionsToRadians ¶
func JointPositionsToRadians(jp *pb.JointPositions) []float64
JointPositionsToRadians converts the given positions into a slice of radians.
func LinkInFrameToTransformProtobuf ¶ added in v0.2.6
func LinkInFrameToTransformProtobuf(framedLink *LinkInFrame) (*commonpb.Transform, error)
LinkInFrameToTransformProtobuf converts a LinkInFrame struct to a Transform protobuf message.
func LinkInFramesToTransformsProtobuf ¶ added in v0.2.6
func LinkInFramesToTransformsProtobuf(linkSlice []*LinkInFrame) ([]*commonpb.Transform, error)
LinkInFramesToTransformsProtobuf converts a slice of LinkInFrame structs to a slice of Transform protobuf messages. TODO(rb): use generics to operate on lists of arbirary types.
func NewDuplicateGeometryNameError ¶ added in v0.2.37
NewDuplicateGeometryNameError returns an error indicating that multiple geometry names have attempted to be registered where this is not allowed.
func NewFrameAlreadyExistsError ¶ added in v0.1.0
NewFrameAlreadyExistsError returns an error indicating that a frame of the given name already exists.
func NewFrameMissingError ¶ added in v0.1.0
NewFrameMissingError returns an error indicating that the given frame is missing from the framesystem.
func NewFrameNotInListOfTransformsError ¶ added in v0.7.0
NewFrameNotInListOfTransformsError returns an error indicating that a frame of the given name is missing from the provided list of transforms.
func NewIncorrectInputLengthError ¶ added in v0.1.0
NewIncorrectInputLengthError returns an error indicating that the length of the Innput array does not match the DoF of the frame.
func NewParentFrameMissingError ¶
NewParentFrameMissingError returns an error for when a part has named a parent whose part is missing from the collection of Parts that are becoming a FrameSystem object.
func NewParentFrameNilError ¶ added in v0.2.47
NewParentFrameNilError returns an error indicating that the parent frame is nil.
func NewParentFrameNotInMapOfParentsError ¶ added in v0.7.0
NewParentFrameNotInMapOfParentsError returns an error indicating that a parent from of the given name is missing from the provided map of parents.
func NewReservedWordError ¶ added in v0.7.0
NewReservedWordError returns an error indicating that the provided name for the config is reserved.
func NewUnsupportedJointTypeError ¶ added in v0.2.5
NewUnsupportedJointTypeError returns an error indicating that a given joint type is not supported by current model parsing.
func PoseInFrameToProtobuf ¶
func PoseInFrameToProtobuf(framedPose *PoseInFrame) *commonpb.PoseInFrame
PoseInFrameToProtobuf converts a PoseInFrame struct to a PoseInFrame protobuf message.
func StartPositions ¶
func StartPositions(fs FrameSystem) map[string][]Input
StartPositions returns a zeroed input map ensuring all frames have inputs.
Types ¶
type DHParamConfig ¶ added in v0.2.6
type DHParamConfig struct { ID string `json:"id"` Parent string `json:"parent"` A float64 `json:"a"` D float64 `json:"d"` Alpha float64 `json:"alpha"` Max float64 `json:"max"` // in mm or degs Min float64 `json:"min"` // in mm or degs Geometry *spatial.GeometryConfig `json:"geometry,omitempty"` }
DHParamConfig is a revolute and static frame combined in a set of Denavit Hartenberg parameters.
func (*DHParamConfig) ToDHFrames ¶ added in v0.2.6
func (cfg *DHParamConfig) ToDHFrames() (Frame, Frame, error)
ToDHFrames converts a DHParamConfig into a joint frame and a link frame.
type Frame ¶
type Frame interface { // Name returns the name of the referenceframe. Name() string // Transform is the pose (rotation and translation) that goes FROM current frame TO parent's referenceframe. Transform([]Input) (spatial.Pose, error) // Geometries returns a map between names and geometries for the reference frame and any intermediate frames that // may be defined for it, e.g. links in an arm. If a frame does not have a geometry it will not be added into the map Geometries([]Input) (*GeometriesInFrame, error) // DoF will return a slice with length equal to the number of joints/degrees of freedom. // Each element describes the min and max movement limit of that joint/degree of freedom. // For robot parts that don't move, it returns an empty slice. DoF() []Limit // InputFromProtobuf does there correct thing for this frame to convert protobuf units (degrees/mm) to input units (radians/mm) InputFromProtobuf(*pb.JointPositions) []Input // ProtobufFromInput does there correct thing for this frame to convert input units (radians/mm) to protobuf units (degrees/mm) ProtobufFromInput([]Input) *pb.JointPositions json.Marshaler }
Frame represents a reference frame, e.g. an arm, a joint, a gripper, a board, etc.
func NewNamedFrame ¶ added in v0.2.50
NewNamedFrame will return a frame which has a new name but otherwise passes through all functions of the original frame.
func NewRotationalFrame ¶
NewRotationalFrame creates a new rotationalFrame struct. A standard revolute joint will have 1 DoF.
func NewStaticFrame ¶
NewStaticFrame creates a frame given a pose relative to its parent. The pose is fixed for all time. Pose is not allowed to be nil.
func NewStaticFrameWithGeometry ¶
func NewStaticFrameWithGeometry(name string, pose spatial.Pose, geometry spatial.Geometry) (Frame, error)
NewStaticFrameWithGeometry creates a frame given a pose relative to its parent. The pose is fixed for all time. It also has an associated geometry representing the space that it occupies in 3D space. Pose is not allowed to be nil.
func NewTranslationalFrame ¶
NewTranslationalFrame creates a frame given a name and the axis in which to translate.
func NewTranslationalFrameWithGeometry ¶
func NewTranslationalFrameWithGeometry(name string, axis r3.Vector, limit Limit, geometry spatial.Geometry) (Frame, error)
NewTranslationalFrameWithGeometry creates a frame given a given a name and the axis in which to translate. It also has an associated geometry representing the space that it occupies in 3D space. Pose is not allowed to be nil.
func NewZeroStaticFrame ¶
NewZeroStaticFrame creates a frame with no translation or orientation changes.
type FrameSystem ¶
type FrameSystem interface { // Name returns the name of this FrameSystem Name() string // World returns the frame corresponding to the root of the FrameSystem, from which other frames are defined with respect to World() Frame // FrameNames returns the names of all of the frames that exist in the FrameSystem FrameNames() []string // Frame returns the Frame in the FrameSystem corresponding to Frame(name string) Frame // AddFrame inserts a given Frame into the FrameSystem as a child of the parent Frame AddFrame(frame, parent Frame) error // RemoveFrame removes the given Frame from the FrameSystem RemoveFrame(frame Frame) // TracebackFrame traces the parentage of the given frame up to the world, and returns the full list of frames in between. // The list will include both the query frame and the world referenceframe TracebackFrame(frame Frame) ([]Frame, error) // Parent returns the parent Frame for the given Frame in the FrameSystem Parent(frame Frame) (Frame, error) // Transform takes in a Transformable object and destination frame, and returns the pose from the first to the second. Positions // is a map of inputs for any frames with non-zero DOF, with slices of inputs keyed to the frame name. Transform(positions map[string][]Input, object Transformable, dst string) (Transformable, error) // FrameSystemSubset will take a frame system and a frame in that system, and return a new frame system rooted // at the given frame and containing all descendents of it. The original frame system is unchanged. FrameSystemSubset(newRoot Frame) (FrameSystem, error) // DivideFrameSystem will take a frame system and a frame in that system, and return a new frame system rooted // at the given frame and containing all descendents of it, while the original has the frame and its // descendents removed. DivideFrameSystem(newRoot Frame) (FrameSystem, error) // MergeFrameSystem combines two frame systems together, placing the world of systemToMerge at the attachTo frame in the frame system MergeFrameSystem(systemToMerge FrameSystem, attachTo Frame) error // ReplaceFrame finds the original frame which shares its name with replacementFrame. We then transfer the original // frame's children and parentage to replacementFrame. The original frame is removed entirely from the frame system. // replacementFrame is not allowed to exist within the frame system at the time of the call. ReplaceFrame(replacementFrame Frame) error }
FrameSystem represents a tree of frames connected to each other, allowing for transformations between any two frames.
func NewEmptyFrameSystem ¶ added in v0.2.47
func NewEmptyFrameSystem(name string) FrameSystem
NewEmptyFrameSystem creates a graph of Frames that have.
func NewFrameSystem ¶ added in v0.2.47
func NewFrameSystem(name string, parts []*FrameSystemPart, additionalTransforms []*LinkInFrame) (FrameSystem, error)
NewFrameSystem assembles a frame system from a set of parts and additional transforms.
type FrameSystemPart ¶ added in v0.2.6
type FrameSystemPart struct { FrameConfig *LinkInFrame ModelFrame Model }
FrameSystemPart is used to collect all the info need from a named robot part to build the frame node in a frame system. FrameConfig gives the frame's location relative to parent, and ModelFrame is an optional ModelJSON that describes the internal kinematics of the robot part.
func LinkInFrameToFrameSystemPart ¶ added in v0.2.6
func LinkInFrameToFrameSystemPart(transform *LinkInFrame) (*FrameSystemPart, error)
LinkInFrameToFrameSystemPart creates a FrameSystem part out of a PoseInFrame.
func ProtobufToFrameSystemPart ¶ added in v0.2.6
func ProtobufToFrameSystemPart(fsc *pb.FrameSystemConfig) (*FrameSystemPart, error)
ProtobufToFrameSystemPart takes a protobuf object and transforms it into a FrameSystemPart.
func TopologicallySortParts ¶ added in v0.2.47
func TopologicallySortParts(parts []*FrameSystemPart) ([]*FrameSystemPart, error)
TopologicallySortParts takes a potentially un-ordered slice of frame system parts and sorts them, beginning at the world node.
func (*FrameSystemPart) ToProtobuf ¶ added in v0.2.6
func (part *FrameSystemPart) ToProtobuf() (*pb.FrameSystemConfig, error)
ToProtobuf turns all the interfaces into serializable types.
type GeometriesInFrame ¶
type GeometriesInFrame struct {
// contains filtered or unexported fields
}
GeometriesInFrame is a data structure that packages geometries with the name of the frame in which it was observed.
func NewGeometriesInFrame ¶
func NewGeometriesInFrame(frame string, geometries []spatialmath.Geometry) *GeometriesInFrame
NewGeometriesInFrame generates a new GeometriesInFrame.
func ProtobufToGeometriesInFrame ¶
func ProtobufToGeometriesInFrame(proto *commonpb.GeometriesInFrame) (*GeometriesInFrame, error)
ProtobufToGeometriesInFrame converts a GeometriesInFrame message as specified in common.proto to a GeometriesInFrame struct.
func (*GeometriesInFrame) Geometries ¶
func (gF *GeometriesInFrame) Geometries() []spatialmath.Geometry
Geometries returns the geometries observed.
func (*GeometriesInFrame) GeometryByName ¶ added in v0.2.24
func (gF *GeometriesInFrame) GeometryByName(name string) spatialmath.Geometry
GeometryByName returns the named geometry if it exists in the GeometriesInFrame, and nil otherwise. If multiple geometries exist with identical names one will be chosen at random.
func (*GeometriesInFrame) Parent ¶ added in v0.2.6
func (gF *GeometriesInFrame) Parent() string
Parent returns the name of the frame in which the geometries were observed.
func (*GeometriesInFrame) Transform ¶
func (gF *GeometriesInFrame) Transform(tf *PoseInFrame) Transformable
Transform changes the GeometriesInFrame gF into the reference frame specified by the tf argument. The tf PoseInFrame represents the pose of the gF reference frame with respect to the destination reference frame.
type Input ¶
type Input struct {
Value float64
}
Input wraps the input to a mutable frame, e.g. a joint angle or a gantry position. Revolute inputs should be in radians. Prismatic inputs should be in mm. TODO: Determine what more this needs, or eschew in favor of raw float64s if nothing needed.
func FloatsToInputs ¶
FloatsToInputs wraps a slice of floats in Inputs.
func GetFrameInputs ¶
GetFrameInputs looks through the inputMap and returns a slice of Inputs corresponding to the given frame.
func InterpolateInputs ¶
InterpolateInputs will return a set of inputs that are the specified percent between the two given sets of inputs. For example, setting by to 0.5 will return the inputs halfway between the from/to values, and 0.25 would return one quarter of the way from "from" to "to".
func RandomFrameInputs ¶
RandomFrameInputs will produce a list of valid, in-bounds inputs for the referenceframe.
func RestrictedRandomFrameInputs ¶
func RestrictedRandomFrameInputs(m Frame, rSeed *rand.Rand, restrictionPercent float64, reference []Input) ([]Input, error)
RestrictedRandomFrameInputs will produce a list of valid, in-bounds inputs for the frame. The range of selection is restricted to `restrictionPercent` percent of the limits, and the selection frame is centered at reference.
type InputEnabled ¶
type InputEnabled interface { CurrentInputs(ctx context.Context) ([]Input, error) GoToInputs(ctx context.Context, goal []Input) error }
InputEnabled is a standard interface for all things that interact with the frame system This allows us to figure out where they currently are, and then move them. Input units are always in meters or radians.
type JointConfig ¶ added in v0.2.6
type JointConfig struct { ID string `json:"id"` Type string `json:"type"` Parent string `json:"parent"` Axis spatial.AxisConfig `json:"axis"` Max float64 `json:"max"` // in mm or degs Min float64 `json:"min"` // in mm or degs Geometry *spatial.GeometryConfig `json:"geometry,omitempty"` // only valid for prismatic/translational joints }
JointConfig is a frame with nonzero DOF. Supports rotational or translational.
func (*JointConfig) ToFrame ¶ added in v0.2.6
func (cfg *JointConfig) ToFrame() (Frame, error)
ToFrame converts a JointConfig into a joint frame.
type LinkConfig ¶ added in v0.2.6
type LinkConfig struct { ID string `json:"id"` Translation r3.Vector `json:"translation"` Orientation *spatial.OrientationConfig `json:"orientation"` Geometry *spatial.GeometryConfig `json:"geometry,omitempty"` Parent string `json:"parent,omitempty"` }
LinkConfig is a StaticFrame that also has a specified parent.
func NewLinkConfig ¶ added in v0.2.6
func NewLinkConfig(frame staticFrame) (*LinkConfig, error)
NewLinkConfig constructs a config from a Frame.
func (*LinkConfig) ParseConfig ¶ added in v0.2.6
func (cfg *LinkConfig) ParseConfig() (*LinkInFrame, error)
ParseConfig converts a LinkConfig into a staticFrame.
type LinkInFrame ¶ added in v0.2.6
type LinkInFrame struct { *PoseInFrame // contains filtered or unexported fields }
LinkInFrame is a PoseInFrame plus a Geometry.
func LinkInFrameFromTransformProtobuf ¶ added in v0.2.6
func LinkInFrameFromTransformProtobuf(proto *commonpb.Transform) (*LinkInFrame, error)
LinkInFrameFromTransformProtobuf converts a Transform protobuf message to a LinkInFrame struct.
func LinkInFramesFromTransformsProtobuf ¶ added in v0.2.6
func LinkInFramesFromTransformsProtobuf(protoSlice []*commonpb.Transform) ([]*LinkInFrame, error)
LinkInFramesFromTransformsProtobuf converts a slice of Transform protobuf messages to a slice of LinkInFrame structs. TODO(rb): use generics to operate on lists of arbirary proto types.
func NewLinkInFrame ¶ added in v0.2.6
func NewLinkInFrame(frame string, pose spatialmath.Pose, name string, geometry spatialmath.Geometry) *LinkInFrame
NewLinkInFrame generates a new LinkInFrame.
func (*LinkInFrame) Geometry ¶ added in v0.2.6
func (lF *LinkInFrame) Geometry() spatialmath.Geometry
Geometry returns the Geometry of the LinkInFrame.
func (*LinkInFrame) ToStaticFrame ¶ added in v0.2.6
func (lF *LinkInFrame) ToStaticFrame(name string) (Frame, error)
ToStaticFrame converts a LinkInFrame into a staticFrame with a new name.
type Model ¶
type Model interface { Frame ModelConfig() *ModelConfig }
A Model represents a frame that can change its name, and can return itself as a ModelConfig struct.
func ModelFromPath ¶ added in v0.2.18
ModelFromPath returns a Model from a given path.
func New2DMobileModelFrame ¶ added in v0.2.50
func New2DMobileModelFrame(name string, limits []Limit, collisionGeometry spatialmath.Geometry) (Model, error)
New2DMobileModelFrame builds the kinematic model associated with the kinematicWheeledBase This model is intended to be used with a mobile base and has either 2DOF corresponding to a state of x, y or has 3DOF corresponding to a state of x, y, and theta, where x and y are the positional coordinates the base is located about and theta is the rotation about the z axis.
func ParseModelJSONFile ¶
ParseModelJSONFile will read a given file and then parse the contained JSON data.
func ParseURDFFile ¶ added in v0.2.5
ParseURDFFile will read a given file and parse the contained URDF XML data into an equivalent ModelConfig struct.
type ModelConfig ¶
type ModelConfig struct { Name string `json:"name"` KinParamType string `json:"kinematic_param_type,omitempty"` Links []LinkConfig `json:"links,omitempty"` Joints []JointConfig `json:"joints,omitempty"` DHParams []DHParamConfig `json:"dhParams,omitempty"` }
ModelConfig represents all supported fields in a kinematics JSON file.
func ConvertURDFToConfig ¶ added in v0.2.5
func ConvertURDFToConfig(xmlData []byte, modelName string) (*ModelConfig, error)
ConvertURDFToConfig will transfer the given URDF XML data into an equivalent ModelConfig. Direct unmarshaling in the same fashion as ModelJSON is not possible, as URDF data will need to be evaluated to accommodate differences between the two kinematics encoding schemes.
func (*ModelConfig) ParseConfig ¶
func (cfg *ModelConfig) ParseConfig(modelName string) (Model, error)
ParseConfig converts the ModelConfig struct into a full Model with the name modelName.
type ModelFramer ¶
type ModelFramer interface {
ModelFrame() Model
}
ModelFramer has a method that returns the kinematics information needed to build a dynamic referenceframe.
type PoseInFrame ¶
type PoseInFrame struct {
// contains filtered or unexported fields
}
PoseInFrame is a data structure that packages a pose with the name of the frame in which it was observed.
func NewPoseInFrame ¶
func NewPoseInFrame(frame string, pose spatialmath.Pose) *PoseInFrame
NewPoseInFrame generates a new PoseInFrame.
func ProtobufToPoseInFrame ¶
func ProtobufToPoseInFrame(proto *commonpb.PoseInFrame) *PoseInFrame
ProtobufToPoseInFrame converts a PoseInFrame protobuf message to a PoseInFrame struct.
func (*PoseInFrame) Name ¶ added in v0.2.4
func (pF *PoseInFrame) Name() string
Name returns the name of the PoseInFrame.
func (*PoseInFrame) Parent ¶ added in v0.2.6
func (pF *PoseInFrame) Parent() string
Parent returns the name of the frame in which the pose was observed. Needed for Transformable interface.
func (*PoseInFrame) Pose ¶
func (pF *PoseInFrame) Pose() spatialmath.Pose
Pose returns the pose that was observed.
func (*PoseInFrame) SetName ¶ added in v0.2.6
func (pF *PoseInFrame) SetName(name string)
SetName sets the name of the PoseInFrame.
func (*PoseInFrame) SetParent ¶ added in v0.2.6
func (pF *PoseInFrame) SetParent(parent string)
SetParent sets the name of the frame in which the pose was observed.
func (*PoseInFrame) Transform ¶
func (pF *PoseInFrame) Transform(tf *PoseInFrame) Transformable
Transform changes the PoseInFrame pF into the reference frame specified by the tf argument. The tf PoseInFrame represents the pose of the pF reference frame with respect to the destination reference frame.
type SimpleModel ¶
type SimpleModel struct { // OrdTransforms is the list of transforms ordered from end effector to base OrdTransforms []Frame // contains filtered or unexported fields }
SimpleModel TODO.
func NewSimpleModel ¶
func NewSimpleModel(name string) *SimpleModel
NewSimpleModel constructs a new model.
func (*SimpleModel) CachedTransform ¶
func (m *SimpleModel) CachedTransform(inputs []Input) (spatialmath.Pose, error)
CachedTransform will check a sync.Map cache to see if the exact given set of inputs has been computed yet. If so it returns without redoing the calculation. Thread safe, but so far has tended to be slightly slower than just doing the calculation. This may change with higher DOF models and longer runtimes.
func (*SimpleModel) DoF ¶
func (m *SimpleModel) DoF() []Limit
DoF returns the number of degrees of freedom within a model.
func (*SimpleModel) Geometries ¶
func (m *SimpleModel) Geometries(inputs []Input) (*GeometriesInFrame, error)
Geometries returns an object representing the 3D space associeted with the staticFrame.
func (*SimpleModel) InputFromProtobuf ¶
func (m *SimpleModel) InputFromProtobuf(jp *pb.JointPositions) []Input
InputFromProtobuf converts pb.JointPosition to inputs.
func (*SimpleModel) MarshalJSON ¶
func (m *SimpleModel) MarshalJSON() ([]byte, error)
MarshalJSON serializes a Model.
func (*SimpleModel) ModelConfig ¶ added in v0.2.6
func (m *SimpleModel) ModelConfig() *ModelConfig
ModelConfig returns the ModelConfig object used to create this model.
func (SimpleModel) Name ¶
func (bf SimpleModel) Name() string
Name returns the name of the referenceframe.
func (*SimpleModel) ProtobufFromInput ¶
func (m *SimpleModel) ProtobufFromInput(input []Input) *pb.JointPositions
ProtobufFromInput converts inputs to pb.JointPosition.
func (*SimpleModel) Transform ¶
func (m *SimpleModel) Transform(inputs []Input) (spatialmath.Pose, error)
Transform takes a model and a list of joint angles in radians and computes the dual quaternion representing the cartesian position of the end effector. This is useful for when conversions between quaternions and OV are not needed.
type Transformable ¶
type Transformable interface { Transform(*PoseInFrame) Transformable Parent() string }
Transformable is an interface to describe elements that can be transformed by the frame system.
type URDFConfig ¶ added in v0.2.5
type URDFConfig struct { XMLName xml.Name `xml:"robot"` Name string `xml:"name,attr"` Links []URDFLink `xml:"link"` Joints []URDFJoint `xml:"joint"` }
URDFConfig represents all supported fields in a Universal Robot Description Format (URDF) file.
type URDFJoint ¶ added in v0.2.5
type URDFJoint struct { XMLName xml.Name `xml:"joint"` Name string `xml:"name,attr"` Type string `xml:"type,attr"` Origin struct { XMLName xml.Name `xml:"origin"` RPY string `xml:"rpy,attr"` // Fixed frame angle "r p y" format, in radians XYZ string `xml:"xyz,attr"` // "x y z" format, in meters } `xml:"origin"` Parent struct { XMLName xml.Name `xml:"parent"` Link string `xml:"link,attr"` } `xml:"parent"` Child struct { XMLName xml.Name `xml:"child"` Link string `xml:"link,attr"` } `xml:"child"` Axis struct { XMLName xml.Name `xml:"axis"` XYZ string `xml:"xyz,attr"` // "x y z" format, in meters } `xml:"axis"` Limit struct { XMLName xml.Name `xml:"limit"` Lower float64 `xml:"lower,attr"` // translation limits are in meters, revolute limits are in radians Upper float64 `xml:"upper,attr"` // translation limits are in meters, revolute limits are in radians } `xml:"limit"` }
URDFJoint is a struct which details the XML used in a URDF joint element.
type URDFLink ¶ added in v0.2.5
type URDFLink struct { XMLName xml.Name `xml:"link"` Name string `xml:"name,attr"` Collision []struct { XMLName xml.Name `xml:"collision"` Name string `xml:"name,attr"` Origin struct { XMLName xml.Name `xml:"origin"` RPY string `xml:"rpy,attr"` // Fixed frame angle "r p y" format, in radians XYZ string `xml:"xyz,attr"` // "x y z" format, in meters } `xml:"origin"` Geometry struct { XMLName xml.Name `xml:"geometry"` Box struct { XMLName xml.Name `xml:"box"` Size string `xml:"size,attr"` // "x y z" format, in meters } `xml:"box"` Sphere struct { XMLName xml.Name `xml:"sphere"` Radius float64 `xml:"radius,attr"` // in meters } `xml:"sphere"` } `xml:"geometry"` } `xml:"collision"` }
URDFLink is a struct which details the XML used in a URDF link element.
type WorldState ¶ added in v0.2.4
type WorldState struct {
// contains filtered or unexported fields
}
WorldState is a struct to store the data representation of the robot's environment.
func NewEmptyWorldState ¶ added in v0.2.37
func NewEmptyWorldState() *WorldState
NewEmptyWorldState is a constructor for a WorldState object that has no obstacles or transforms.
func NewWorldState ¶ added in v0.2.37
func NewWorldState(obstacles []*GeometriesInFrame, transforms []*LinkInFrame) (*WorldState, error)
NewWorldState is a constructor for a WorldState object.
func WorldStateFromProtobuf ¶ added in v0.2.4
func WorldStateFromProtobuf(proto *commonpb.WorldState) (*WorldState, error)
WorldStateFromProtobuf takes the protobuf definition of a WorldState and converts it to a rdk defined WorldState.
func (*WorldState) ObstacleNames ¶ added in v0.2.37
func (ws *WorldState) ObstacleNames() map[string]bool
ObstacleNames returns the set of geometry names that have been registered in the WorldState, represented as a map.
func (*WorldState) ObstaclesInWorldFrame ¶ added in v0.2.32
func (ws *WorldState) ObstaclesInWorldFrame(fs FrameSystem, inputs map[string][]Input) (*GeometriesInFrame, error)
ObstaclesInWorldFrame takes a frame system and a set of inputs for that frame system and converts all the obstacles in the WorldState such that they are in the frame system's World reference frame.
func (*WorldState) String ¶ added in v0.2.50
func (ws *WorldState) String() string
String returns a string representation of the geometries in the WorldState.
func (*WorldState) ToProtobuf ¶ added in v0.2.37
func (ws *WorldState) ToProtobuf() (*commonpb.WorldState, error)
ToProtobuf takes an rdk WorldState and converts it to the protobuf definition of a WorldState.
func (*WorldState) Transforms ¶ added in v0.2.4
func (ws *WorldState) Transforms() []*LinkInFrame
Transforms returns the transforms that have been added to the WorldState.