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 AreInputsValid(ls []Limit, values []float64) bool
- func FrameSystemGeometries(fs *FrameSystem, inputMap FrameSystemInputs) (map[string]*GeometriesInFrame, error)
- func FrameSystemGeometriesLinearInputs(fs *FrameSystem, linearInputs *LinearInputs) (map[string]*GeometriesInFrame, error)
- func FrameSystemToPCD(system *FrameSystem, inputs FrameSystemInputs, logger logging.Logger) (map[string][]r3.Vector, error)
- func GenerateRandomConfiguration(m Model, randSeed *rand.Rand) []float64
- func GeoGeometryFromProtobuf(protoGeoObst *commonpb.GeoGeometry) (*spatialmath.GeoGeometry, error)
- func GeoGeometryToProtobuf(geoObst *spatialmath.GeoGeometry) *commonpb.GeoGeometry
- func GeometriesInFrameToProtobuf(framedGeometries *GeometriesInFrame) *commonpb.GeometriesInFrame
- func InputsL2Distance(from, to []Input) float64
- func InputsLinfDistance(from, to []Input) float64
- func JointPositionsFromInputs(f Frame, inputs []Input) (*pb.JointPositions, error)
- func JointPositionsFromRadians(radians []float64) *pb.JointPositions
- func JointPositionsToRadians(jp *pb.JointPositions) []float64
- func KinematicModelToProtobuf(model Model) *commonpb.GetKinematicsResponse
- func LinkInFrameToTransformProtobuf(framedLink *LinkInFrame) (*commonpb.Transform, error)
- func LinkInFramesToTransformsProtobuf(linkSlice []*LinkInFrame) ([]*commonpb.Transform, error)
- func NewDuplicateFrameNameError(frameName string) error
- func NewDuplicateGeometryNameError(name string) error
- func NewFrameAlreadyExistsError(frameName string) error
- func NewFrameMissingError(frameName string) error
- func NewFrameNotInListOfTransformsError(frameName string) error
- func NewGeometriesFromProto(proto []*commonpb.Geometry) ([]spatialmath.Geometry, error)
- func NewGeometriesToProto(geometries []spatialmath.Geometry) []*commonpb.Geometry
- func NewGeometryFromProto(geometry *commonpb.Geometry) (spatialmath.Geometry, error)
- func NewIncorrectDoFError(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 RegisterFrameImplementer(frame Frame, name string) error
- func TopologicallySortParts(parts []*FrameSystemPart) ([]*FrameSystemPart, []*FrameSystemPart)
- type DHParamConfig
- type Frame
- func NewNamedFrame(frame Frame, name string) Frame
- func NewPoseFrame(name string, geometry []spatial.Geometry) (Frame, error)
- 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
- func (sfs *FrameSystem) AddFrame(frame, parent Frame) error
- func (sfs *FrameSystem) DivideFrameSystem(newRoot Frame) (*FrameSystem, error)
- func (sfs *FrameSystem) Frame(name string) Frame
- func (sfs *FrameSystem) FrameNames() []string
- func (sfs *FrameSystem) FrameSystemSubset(newRoot Frame) (*FrameSystem, error)
- func (sfs *FrameSystem) GetFrameToWorldTransform(inputs *LinearInputs, src Frame) (dualquat.Number, error)
- func (sfs *FrameSystem) Hash() int
- func (sfs *FrameSystem) MarshalJSON() ([]byte, error)
- func (sfs *FrameSystem) MergeFrameSystem(systemToMerge *FrameSystem, attachTo Frame) error
- func (sfs *FrameSystem) Name() string
- func (sfs *FrameSystem) Parent(frame Frame) (Frame, error)
- func (sfs *FrameSystem) RemoveFrame(frame Frame)
- func (sfs *FrameSystem) ReplaceFrame(replacementFrame Frame) error
- func (sfs *FrameSystem) TracebackFrame(query Frame) ([]Frame, error)
- func (sfs *FrameSystem) Transform(inputs *LinearInputs, object Transformable, dst string) (Transformable, error)
- func (sfs *FrameSystem) TransformToDQ(inputs *LinearInputs, frame, parent string) (spatial.DualQuaternion, error)
- func (sfs *FrameSystem) UnmarshalJSON(data []byte) error
- func (sfs *FrameSystem) World() Frame
- type FrameSystemInputs
- type FrameSystemPart
- type FrameSystemPoses
- type GeometriesInFrame
- type Input
- func InputsFromJointPositions(f Frame, jp *pb.JointPositions) ([]Input, error)
- func PoseToInputs(p spatial.Pose) []Input
- func RandomFrameInputs(m Frame, rSeed *rand.Rand) []Input
- func RestrictedRandomFrameInputs(m Frame, rSeed *rand.Rand, restrictionPercent float64, reference []Input) ([]Input, error)
- type JointConfig
- type Limit
- type Limited
- type LinearInputs
- func (li *LinearInputs) ComputePoses(fs *FrameSystem) (FrameSystemPoses, error)
- func (li *LinearInputs) CopyWithZeros() *LinearInputs
- func (li *LinearInputs) Get(frameName string) []Input
- func (li *LinearInputs) GetFrameInputs(frame Frame) ([]Input, error)
- func (li *LinearInputs) GetLinearizedInputs() []Input
- func (li *LinearInputs) GetSchema(fs *FrameSystem) (*LinearInputsSchema, error)
- func (li *LinearInputs) Items() iter.Seq2[string, []Input]
- func (li *LinearInputs) Keys() iter.Seq[string]
- func (li *LinearInputs) Len() int
- func (li *LinearInputs) Put(frameName string, inputs []Input)
- func (li *LinearInputs) ToFrameSystemInputs() FrameSystemInputs
- type LinearInputsSchema
- type LinkConfig
- type LinkInFrame
- type Model
- func KinematicModelFromFile(modelPath, name string) (Model, error)
- func KinematicModelFromProtobuf(name string, resp *commonpb.GetKinematicsResponse) (Model, error)
- func New2DMobileModelFrame(name string, limits []Limit, collisionGeometry spatialmath.Geometry) (Model, error)
- func ParseModelJSONFile(filename, modelName string) (Model, error)
- func ParseModelXMLFile(filename, modelName string) (Model, error)
- func UnmarshalModelJSON(jsonData []byte, modelName string) (Model, error)
- type ModelConfigJSON
- type ModelConfigURDF
- type ModelFile
- type PoseInFrame
- func (pF *PoseInFrame) MarshalJSON() ([]byte, error)
- func (pF *PoseInFrame) Name() string
- func (pF *PoseInFrame) Parent() string
- func (pF *PoseInFrame) Pose() spatialmath.Pose
- func (pF *PoseInFrame) SetName(name string)
- func (pF *PoseInFrame) SetParent(parent string)
- func (pF *PoseInFrame) String() string
- func (pF *PoseInFrame) Transform(tf *PoseInFrame) Transformable
- func (pF *PoseInFrame) TransformOpt(tf *PoseInFrame)
- func (pF *PoseInFrame) UnmarshalJSON(data []byte) error
- type SimpleModel
- func NewModel(name string, fs *FrameSystem, primaryOutputFrame string) (*SimpleModel, error)
- func NewModelWithLimitOverrides(base *SimpleModel, overrides map[string]Limit) (*SimpleModel, error)
- func NewSerialModel(name string, frames []Frame) (*SimpleModel, error)
- func NewSimpleModel(name string) *SimpleModel
- func (m *SimpleModel) DoF() []Limit
- func (m *SimpleModel) Geometries(inputs []Input) (*GeometriesInFrame, error)
- func (m *SimpleModel) Hash() int
- func (m *SimpleModel) InputFromProtobuf(jp *pb.JointPositions) []Input
- func (m *SimpleModel) Interpolate(from, to []Input, by float64) ([]Input, error)
- func (m *SimpleModel) MarshalJSON() ([]byte, error)
- func (m *SimpleModel) ModelConfig() *ModelConfigJSON
- func (m *SimpleModel) MoveableFrameNames() []string
- func (bf *SimpleModel) Name() string
- func (m *SimpleModel) ProtobufFromInput(input []Input) *pb.JointPositions
- func (m *SimpleModel) Transform(inputs []Input) (spatialmath.Pose, error)
- func (m *SimpleModel) UnmarshalJSON(data []byte) error
- type Transformable
- type WorldState
- func (ws *WorldState) MarshalJSON() ([]byte, error)
- func (ws *WorldState) ObstacleNames() map[string]bool
- func (ws *WorldState) Obstacles() []*GeometriesInFrame
- func (ws *WorldState) ObstaclesInWorldFrame(fs *FrameSystem, inputs FrameSystemInputs) (*GeometriesInFrame, error)
- func (ws *WorldState) String() string
- func (ws *WorldState) ToProtobuf() (*commonpb.WorldState, error)
- func (ws *WorldState) Transforms() []*LinkInFrame
- func (ws *WorldState) UnmarshalJSON(data []byte) error
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 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 ErrNeedOneEndEffector = errors.New("need exactly one end effector")
ErrNeedOneEndEffector is an error indicating that exactly one end effector is required.
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 AreInputsValid ¶ added in v0.104.0
AreInputsValid checks if all values are within limit ranges
func FrameSystemGeometries ¶ added in v0.2.15
func FrameSystemGeometries(fs *FrameSystem, inputMap FrameSystemInputs) (map[string]*GeometriesInFrame, error)
FrameSystemGeometries takes in a framesystem and returns a map where all elements are GeometriesInFrames with a World reference frame. `FrameSystemGeometriesLinearInputs` is preferred for hot paths. This function is otherwise kept around for backwards compatibility.
func FrameSystemGeometriesLinearInputs ¶ added in v0.100.0
func FrameSystemGeometriesLinearInputs(fs *FrameSystem, linearInputs *LinearInputs) (map[string]*GeometriesInFrame, error)
FrameSystemGeometriesLinearInputs takes in a framesystem and returns a LinearInputs where all elements are GeometriesInFrames with a World reference frame. This is preferred for hot paths. But requires the caller to manage a `LinearInputs`.
func FrameSystemToPCD ¶ added in v0.2.15
func FrameSystemToPCD(system *FrameSystem, inputs FrameSystemInputs, 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 GeoGeometryFromProtobuf ¶ added in v0.91.0
func GeoGeometryFromProtobuf(protoGeoObst *commonpb.GeoGeometry) (*spatialmath.GeoGeometry, error)
GeoGeometryFromProtobuf takes a Protobuf representation of a GeoGeometry and converts back into a Go struct.
func GeoGeometryToProtobuf ¶ added in v0.91.0
func GeoGeometryToProtobuf(geoObst *spatialmath.GeoGeometry) *commonpb.GeoGeometry
GeoGeometryToProtobuf converts the GeoGeometry struct into an equivalent Protobuf message.
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 (the sqrt of the sum of the squares) between two Input sets.
func InputsLinfDistance ¶ added in v0.85.0
InputsLinfDistance returns the inf-norm between two Input sets.
func JointPositionsFromInputs ¶ added in v0.49.0
func JointPositionsFromInputs(f Frame, inputs []Input) (*pb.JointPositions, error)
JointPositionsFromInputs converts the given slice of Input to a JointPositions struct, using the ProtobufFromInput function provided by the given Frame.
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 KinematicModelToProtobuf ¶ added in v0.78.0
func KinematicModelToProtobuf(model Model) *commonpb.GetKinematicsResponse
KinematicModelToProtobuf converts a model into a protobuf message version of that model.
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 NewDuplicateFrameNameError ¶ added in v0.114.0
NewDuplicateFrameNameError returns an error indicating that multiple frames with the same name were provided.
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 NewGeometriesFromProto ¶ added in v0.91.0
func NewGeometriesFromProto(proto []*commonpb.Geometry) ([]spatialmath.Geometry, error)
NewGeometriesFromProto converts a list of Geometries from protobuf.
func NewGeometriesToProto ¶ added in v0.91.0
func NewGeometriesToProto(geometries []spatialmath.Geometry) []*commonpb.Geometry
NewGeometriesToProto converts a list of Geometries to profobuf.
func NewGeometryFromProto ¶ added in v0.91.0
func NewGeometryFromProto(geometry *commonpb.Geometry) (spatialmath.Geometry, error)
NewGeometryFromProto instantiates a new Geometry from a protobuf Geometry message.
func NewIncorrectDoFError ¶ added in v0.49.0
NewIncorrectDoFError returns an error indicating that the length of the 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 RegisterFrameImplementer ¶ added in v0.85.0
RegisterFrameImplementer allows outside packages to register their implementations of the Frame interface for serialization/deserialization with the given name.
func TopologicallySortParts ¶ added in v0.2.47
func TopologicallySortParts(parts []*FrameSystemPart) ([]*FrameSystemPart, []*FrameSystemPart)
TopologicallySortParts takes a potentially un-ordered slice of frame system parts and sorts them, beginning at the world node. The world frame is not included in the output.
Parts that are missing a parent will be ignored and returned as part of the second return value. If it's important that all inputs are connected to the world frame, a caller must conditionally error on that second return value.
Given each node can only have one parent, and we always return the tree rooted at the world frame, cycles are impossible. The "unlinked" second return value might be unlinked because a parent does not exist, or the nodes are in a cycle with each other.
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 {
Limited
// Name returns the name of the Frame
Name() string
Hash() int
// Transform is the pose (rotation and translation) that goes FROM current frame TO parent's
// reference frame.
//
// If the transform cannot be computed (including if inputs are out of bounds), the returned
// pose will be nil and the error will not be nil.
Transform([]Input) (spatial.Pose, error)
// Interpolate interpolates the given amount between the two sets of inputs.
Interpolate([]Input, []Input, float64) ([]Input, 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)
// 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
json.Unmarshaler
}
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 NewPoseFrame ¶ added in v0.37.0
NewPoseFrame creates an orientation vector frame, i.e a frame with 7 degrees of freedom: X, Y, Z, OX, OY, OZ, and Theta in radians.
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 struct {
// contains filtered or unexported fields
}
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.
func (*FrameSystem) AddFrame ¶
func (sfs *FrameSystem) AddFrame(frame, parent Frame) error
AddFrame sets an already defined Frame into the system.
func (*FrameSystem) DivideFrameSystem ¶
func (sfs *FrameSystem) DivideFrameSystem(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. For example, if there is a frame system with two independent rovers, and one rover goes offline, A user could divide the frame system to remove the offline rover and have the rest of the frame system unaffected.
func (*FrameSystem) Frame ¶ added in v0.1.0
func (sfs *FrameSystem) Frame(name string) Frame
Frame returns the Frame which has the provided name. It returns nil if the frame is not found in the FraneSystem.
func (*FrameSystem) FrameNames ¶
func (sfs *FrameSystem) FrameNames() []string
FrameNames returns the list of frame names registered in the frame system.
func (*FrameSystem) FrameSystemSubset ¶ added in v0.1.0
func (sfs *FrameSystem) FrameSystemSubset(newRoot Frame) (*FrameSystem, 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.
func (*FrameSystem) GetFrameToWorldTransform ¶ added in v0.99.0
func (sfs *FrameSystem) GetFrameToWorldTransform(inputs *LinearInputs, src Frame) (dualquat.Number, error)
GetFrameToWorldTransform computes the position of src in the world frame based on inputMap.
func (*FrameSystem) Hash ¶ added in v0.99.0
func (sfs *FrameSystem) Hash() int
Hash returns a hash value for this frame system.
func (*FrameSystem) MarshalJSON ¶ added in v0.85.0
func (sfs *FrameSystem) MarshalJSON() ([]byte, error)
MarshalJSON serializes a FrameSystem into JSON format.
func (*FrameSystem) MergeFrameSystem ¶
func (sfs *FrameSystem) MergeFrameSystem(systemToMerge *FrameSystem, attachTo Frame) error
MergeFrameSystem will combine two frame systems together, placing the world of systemToMerge at the "attachTo" frame in sfs. The frame where systemToMerge will be attached to must already exist within sfs, so should be added before Merge happens. Merging is necessary when including remote robots, dynamically building systems of robots, or mutating a robot after it has already been initialized. For example, two independent rovers, each with their own frame system, need to now know where they are in relation to each other and need to have their frame systems combined.
func (*FrameSystem) Name ¶
func (sfs *FrameSystem) Name() string
Name returns the name of the simpleFrameSystem.
func (*FrameSystem) Parent ¶
func (sfs *FrameSystem) Parent(frame Frame) (Frame, error)
Parent returns the parent Frame of the given Frame. It will return nil if the given frame is World.
func (*FrameSystem) RemoveFrame ¶
func (sfs *FrameSystem) RemoveFrame(frame Frame)
RemoveFrame will delete the given frame and all descendents from the frame system if it exists.
func (*FrameSystem) ReplaceFrame ¶ added in v0.10.0
func (sfs *FrameSystem) ReplaceFrame(replacementFrame 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.
func (*FrameSystem) TracebackFrame ¶
func (sfs *FrameSystem) TracebackFrame(query Frame) ([]Frame, error)
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, and is ordered from query to world.
func (*FrameSystem) Transform ¶
func (sfs *FrameSystem) Transform(inputs *LinearInputs, object Transformable, dst string) (Transformable, 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.
func (*FrameSystem) TransformToDQ ¶ added in v0.100.0
func (sfs *FrameSystem) TransformToDQ(inputs *LinearInputs, frame, parent string) ( spatial.DualQuaternion, error, )
TransformToDQ is like `Transform` except it outputs a `DualQuaternion` that can be converted into a `Pose`. The advantage of being more manual is to avoid memory allocations when unnecessary. As only a pointer to a `DualQuaternion` satisfies the `Pose` interface.
This also avoids an allocation by accepting a frame name as the input rather than a `Transformable`. Saving the caller from making an allocation if the resulting pose is the only desired output.
func (*FrameSystem) UnmarshalJSON ¶ added in v0.85.0
func (sfs *FrameSystem) UnmarshalJSON(data []byte) error
UnmarshalJSON parses a FrameSystem from JSON data.
func (*FrameSystem) World ¶
func (sfs *FrameSystem) World() Frame
World returns the root of the frame system, which is always named "world".
type FrameSystemInputs ¶ added in v0.58.0
FrameSystemInputs is an alias for a mapping of frame names to slices of Inputs.
func NewZeroInputs ¶ added in v0.58.0
func NewZeroInputs(fs *FrameSystem) FrameSystemInputs
NewZeroInputs returns a zeroed FrameSystemInputs ensuring all frames have inputs.
func (FrameSystemInputs) ComputePoses ¶ added in v0.58.0
func (inputs FrameSystemInputs) ComputePoses(fs *FrameSystem) (FrameSystemPoses, error)
ComputePoses computes the poses for each frame in a framesystem in frame of World, using the provided configuration.
func (FrameSystemInputs) GetFrameInputs ¶ added in v0.58.0
func (inputs FrameSystemInputs) GetFrameInputs(frame Frame) ([]Input, error)
GetFrameInputs returns the inputs corresponding to the given frame within the FrameSystemInputs object.
func (FrameSystemInputs) ToLinearInputs ¶ added in v0.100.0
func (inputs FrameSystemInputs) ToLinearInputs() *LinearInputs
ToLinearInputs turns this structured map into a flat map of `LinearInputs`. The flat map will internally be in frame name order.
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 (*FrameSystemPart) ToProtobuf ¶ added in v0.2.6
func (part *FrameSystemPart) ToProtobuf() (*pb.FrameSystemConfig, error)
ToProtobuf turns all the interfaces into serializable types.
type FrameSystemPoses ¶ added in v0.58.0
type FrameSystemPoses map[string]*PoseInFrame
FrameSystemPoses is an alias for a mapping of frame names to PoseInFrame.
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 = float64
Input represents 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.
func InputsFromJointPositions ¶ added in v0.49.0
func InputsFromJointPositions(f Frame, jp *pb.JointPositions) ([]Input, error)
InputsFromJointPositions converts the given JointPositions struct to a slice of Input, using the ProtobufFromInput function provided by the given Frame.
func PoseToInputs ¶ added in v0.37.0
PoseToInputs is a convenience method for turning a pose into a slice of inputs in the form [X, Y, Z, OX, OY, OZ, Theta (in radians)] This is the format that is expected by the poseFrame type and should not be used with other frames.
func RandomFrameInputs ¶
RandomFrameInputs will produce a list of valid, in-bounds inputs for the Frame.
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 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 Limit ¶
Limit represents the limits of motion for a Frame.
func (*Limit) GoodLimits ¶ added in v0.98.0
GoodLimits gives min, max, range, but capped to -999,999.
type Limited ¶ added in v0.18.0
type Limited interface {
// DoF will return a slice with length equal to the number of degrees of freedom. Each element
// describes the min and max movement limit of that degree of freedom. For robot parts that
// don't move, it returns an empty slice.
DoF() []Limit
}
Limited represents anything that has Limits.
type LinearInputs ¶ added in v0.100.0
type LinearInputs struct {
// contains filtered or unexported fields
}
LinearInputs is a memory optimized representation of FrameSystemInputs. The type is expected to only be used by direct consumers of the frame system library.
func InterpolateFS ¶ added in v0.54.0
func InterpolateFS(fs *FrameSystem, from, to *LinearInputs, by float64) (*LinearInputs, error)
InterpolateFS interpolates.
func NewLinearInputs ¶ added in v0.100.0
func NewLinearInputs() *LinearInputs
NewLinearInputs initializes a LinearInputs.
func NewZeroLinearInputs ¶ added in v0.100.0
func NewZeroLinearInputs(fs *FrameSystem) *LinearInputs
NewZeroLinearInputs returns a zeroed LinearInputs ensuring all frames have inputs.
func (*LinearInputs) ComputePoses ¶ added in v0.100.0
func (li *LinearInputs) ComputePoses(fs *FrameSystem) (FrameSystemPoses, error)
ComputePoses computes the poses for each frame in a framesystem in frame of World, using the provided configuration.
func (*LinearInputs) CopyWithZeros ¶ added in v0.101.0
func (li *LinearInputs) CopyWithZeros() *LinearInputs
CopyWithZeros makes a new copy with everything zero
func (*LinearInputs) Get ¶ added in v0.100.0
func (li *LinearInputs) Get(frameName string) []Input
Get returns the inputs associated with a frame name.
func (*LinearInputs) GetFrameInputs ¶ added in v0.100.0
func (li *LinearInputs) GetFrameInputs(frame Frame) ([]Input, error)
GetFrameInputs returns the inputs corresponding to the given frame within the LinearInputs object. This method returns an error if the frame has non-zero DoF and the frame name does not exist.
func (*LinearInputs) GetLinearizedInputs ¶ added in v0.100.0
func (li *LinearInputs) GetLinearizedInputs() []Input
GetLinearizedInputs returns the flat array of floats. Used for communicating with IK/nlopt.
func (*LinearInputs) GetSchema ¶ added in v0.100.0
func (li *LinearInputs) GetSchema(fs *FrameSystem) (*LinearInputsSchema, error)
GetSchema returns the underlying `LinearInputsSchema` associated with this LinearInputs. When using this LinearInputs to create inputs for IK/nlopt, this returned `LinearInputsSchema` is how to turn the IK/nlopt output back into frames inputs. The `FrameSystem` is an additional input such that we can ensure the proper joint limits are assigned.
func (*LinearInputs) Items ¶ added in v0.100.0
func (li *LinearInputs) Items() iter.Seq2[string, []Input]
Items returns an iterator over the key-value pairs in this `LinearInputs`. This is analogous to the key/value ranging over a map.
func (*LinearInputs) Keys ¶ added in v0.100.0
func (li *LinearInputs) Keys() iter.Seq[string]
Keys returns an iterator over the keys. This is analogous to ranging over the keys of a map.
func (*LinearInputs) Len ¶ added in v0.100.0
func (li *LinearInputs) Len() int
Len returns how many frames (included 0-DoF frames) are in the LinearInputs.
func (*LinearInputs) Put ¶ added in v0.100.0
func (li *LinearInputs) Put(frameName string, inputs []Input)
Put adds a new frameName -> inputs mapping. Put will overwrite an existing mapping when the frame name matches and the input value is of the same DoF as the prior mapping. Put will silently ignore the request if an overwrite has a different DoF than the original. That is considered programmer error.
func (*LinearInputs) ToFrameSystemInputs ¶ added in v0.100.0
func (li *LinearInputs) ToFrameSystemInputs() FrameSystemInputs
ToFrameSystemInputs creates a `FrameSystemInputs` with the same keys and values. This is a convenience method for interfacing with higher level public APIs that don't need to be as efficient.
type LinearInputsSchema ¶ added in v0.100.0
type LinearInputsSchema struct {
// contains filtered or unexported fields
}
LinearInputsSchema describes the order of frame names and their degrees of freedom in a set of Inputs. This is important for communicating consistently with IK/nlopt.
func (*LinearInputsSchema) FloatsToInputs ¶ added in v0.100.0
func (lis *LinearInputsSchema) FloatsToInputs(inps []float64) (*LinearInputs, error)
FloatsToInputs applies the given schema to a new set of linearized floats. This returns an error if the wrong number of floats are provided.
func (*LinearInputsSchema) FrameNamesInOrder ¶ added in v0.100.0
func (lis *LinearInputsSchema) FrameNamesInOrder() []string
FrameNamesInOrder returns the frame names in schema order.
func (*LinearInputsSchema) GetLimits ¶ added in v0.100.0
func (lis *LinearInputsSchema) GetLimits() []Limit
GetLimits returns the limits associated with the frames in the linearized order expected by nlopt.
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 Frame) (*LinkConfig, error)
NewLinkConfig constructs a config from a Frame. NOTE: this currently only works with Frames of len(DoF)==0 and will error otherwise NOTE: this will not work if more than one Geometry is returned by the Geometries function.
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() *ModelConfigJSON
}
A Model represents a frame that can change its name, and can return itself as a ModelConfig struct.
func KinematicModelFromFile ¶ added in v0.78.0
KinematicModelFromFile returns a model frame from a file that defines the kinematics.
func KinematicModelFromProtobuf ¶ added in v0.78.0
func KinematicModelFromProtobuf(name string, resp *commonpb.GetKinematicsResponse) (Model, error)
KinematicModelFromProtobuf returns a model from a protobuf message representing it.
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 ParseModelXMLFile ¶ added in v0.78.0
ParseModelXMLFile will read a given file and parse the contained URDF XML data into an equivalent Model. It automatically loads mesh files referenced in the URDF from the local filesystem.
type ModelConfigJSON ¶ added in v0.78.0
type ModelConfigJSON 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"`
OutputFrames []string `json:"output_frames,omitempty"`
OriginalFile *ModelFile
}
ModelConfigJSON represents all supported fields in a kinematics JSON file.
func UnmarshalModelXML ¶ added in v0.78.0
func UnmarshalModelXML(xmlData []byte, modelName string, meshMap map[string]*commonpb.Mesh) (*ModelConfigJSON, error)
UnmarshalModelXML 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. The meshMap parameter provides mesh proto messages keyed by URDF file path (e.g., "meshes/base.stl" -> proto Mesh).
func (*ModelConfigJSON) ParseConfig ¶ added in v0.78.0
func (cfg *ModelConfigJSON) ParseConfig(modelName string) (Model, error)
ParseConfig converts the ModelConfig struct into a full Model with the name modelName.
type ModelConfigURDF ¶ added in v0.78.0
type ModelConfigURDF struct {
XMLName xml.Name `xml:"robot"`
Name string `xml:"name,attr"`
Links []linkXML `xml:"link"`
Joints []jointXML `xml:"joint"`
}
ModelConfigURDF represents all supported fields in a Universal Robot Description Format (URDF) file.
func NewModelFromWorldState ¶ added in v0.78.0
func NewModelFromWorldState(ws *WorldState, name string) (*ModelConfigURDF, error)
NewModelFromWorldState creates a ModelConfigURDF struct which can be marshalled into xml and will be a valid .urdf file representing the geometries in the given worldstate.
type ModelFile ¶ added in v0.15.0
ModelFile is a struct that stores the raw bytes of the file used to create the model as well as its extension, which is useful for knowing how to unmarhsal it.
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 NewZeroPoseInFrame ¶ added in v0.54.0
func NewZeroPoseInFrame(frame string) *PoseInFrame
NewZeroPoseInFrame is a convenience method that creates a PoseInFrame with the specified Frame and a zero pose.
func ProtobufToPoseInFrame ¶
func ProtobufToPoseInFrame(proto *commonpb.PoseInFrame) *PoseInFrame
ProtobufToPoseInFrame converts a PoseInFrame protobuf message to a PoseInFrame struct.
func (*PoseInFrame) MarshalJSON ¶ added in v0.84.0
func (pF *PoseInFrame) MarshalJSON() ([]byte, error)
MarshalJSON converts a PoseInFrame to JSON through its protobuf representation.
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) String ¶ added in v0.27.0
func (pF *PoseInFrame) String() string
String returns the string representation of the PoseInFrame.
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.
func (*PoseInFrame) TransformOpt ¶ added in v0.100.0
func (pF *PoseInFrame) TransformOpt(tf *PoseInFrame)
TransformOpt transforms the `pF` as a DualQuaternion in place.
func (*PoseInFrame) UnmarshalJSON ¶ added in v0.84.0
func (pF *PoseInFrame) UnmarshalJSON(data []byte) error
UnmarshalJSON parses a PoseInFrame from its protobuf representation in JSON bytes.
type SimpleModel ¶
type SimpleModel struct {
// contains filtered or unexported fields
}
SimpleModel is a model that uses an internal FrameSystem to represent its kinematic tree. It supports both serial chains and branching tree topologies (e.g. grippers with branching fingers). A user-specified "primary output frame" determines what Transform() returns.
func NewModel ¶ added in v0.115.0
func NewModel(name string, fs *FrameSystem, primaryOutputFrame string) (*SimpleModel, error)
NewModel constructs a model from a FrameSystem and a primary output frame. The primary output frame must exist in fs and determines what Transform() returns.
func NewModelWithLimitOverrides ¶ added in v0.114.0
func NewModelWithLimitOverrides(base *SimpleModel, overrides map[string]Limit) (*SimpleModel, error)
NewModelWithLimitOverrides constructs a new model identical to base but with the specified joint limits overridden. Overrides are keyed by frame name. Each override replaces the first DoF limit of the matching frame.
func NewSerialModel ¶ added in v0.114.0
func NewSerialModel(name string, frames []Frame) (*SimpleModel, error)
NewSerialModel is a convenience constructor that builds a Model from a serial chain of frames. Returns an error if duplicate frame names are detected.
func NewSimpleModel ¶
func NewSimpleModel(name string) *SimpleModel
NewSimpleModel constructs a new empty model with no kinematics.
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 the geometries for all frames in the model, placed in world coordinates.
func (*SimpleModel) Hash ¶ added in v0.99.0
func (m *SimpleModel) Hash() int
Hash returns a hash value for this simple model.
func (*SimpleModel) InputFromProtobuf ¶
func (m *SimpleModel) InputFromProtobuf(jp *pb.JointPositions) []Input
InputFromProtobuf converts pb.JointPosition to inputs.
func (*SimpleModel) Interpolate ¶ added in v0.25.0
func (m *SimpleModel) Interpolate(from, to []Input, by float64) ([]Input, error)
Interpolate interpolates the given amount between the two sets of 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() *ModelConfigJSON
ModelConfig returns the ModelConfig object used to create this model.
func (*SimpleModel) MoveableFrameNames ¶ added in v0.114.0
func (m *SimpleModel) MoveableFrameNames() []string
MoveableFrameNames returns the names of frames with non-zero DoF, in schema order.
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 returns the pose of the primary output frame given the flat input vector. When inputs are out of bounds, Transform returns both the computed pose and an OOB error.
func (*SimpleModel) UnmarshalJSON ¶ added in v0.85.0
func (m *SimpleModel) UnmarshalJSON(data []byte) error
UnmarshalJSON deserializes a Model.
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 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 instantiates a WorldState with geometries which are meant to represent obstacles and transforms which are meant to represent additional links that augment a FrameSystem.
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) MarshalJSON ¶ added in v0.84.0
func (ws *WorldState) MarshalJSON() ([]byte, error)
MarshalJSON serializes an instance of WorldState to JSON through its protobuf representation.
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) Obstacles ¶ added in v0.2.4
func (ws *WorldState) Obstacles() []*GeometriesInFrame
Obstacles returns the obstacles that have been added to the WorldState.
func (*WorldState) ObstaclesInWorldFrame ¶ added in v0.2.32
func (ws *WorldState) ObstaclesInWorldFrame(fs *FrameSystem, inputs FrameSystemInputs) (*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.
func (*WorldState) UnmarshalJSON ¶ added in v0.84.0
func (ws *WorldState) UnmarshalJSON(data []byte) error
UnmarshalJSON takes JSON bytes of a world state protobuf message and parses it into an instance of WorldState.