A coordinate frame that is rigidly attached to the origin a rigid joint and the child link of the joint. In addition, this class stores the type, rotation axis, child link, and limit of the rigid joints. More...

Inheritance diagram for RigidJoint:
[legend]

Public Member Functions

 RigidJoint (varargin)
 The class constructor function. More...
 
function obj = setAxis (rowvec axis)
 set the joint rotation axis vector in the joint coordinate More...
 
function obj = setType (char type)
 Sets the joint type. More...
 
function obj = setParent (char parent)
 set the parent link frame More...
 
function obj = setChild (char child)
 set the child link frame More...
 
function obj = setLimit (varargin)
 set the physical limits of the rigid joints More...
 
function obj = setActuator (varargin)
 set the physical limits of the rigid joints More...
 
function obj = setChainIndices (rowvec indices)
 Set the kinematic chain indices of the parent reference frames. More...
 
function xi = getTwist ()
 returns the twist vector of the rigid joint More...
 
function obj = computeTwist ()
 computes the twist from the base frame More...
 
function obj = setTwistPairs (RigitJoint dofs,SymVariable q)
 set the twist paris of all precedent joints More...
 
- Public Member Functions inherited from CoordinateFrame
 CoordinateFrame (varargin)
 The class constructor function. More...
 
function obj = ToContactFrame (char type)
 convert a coordinate frame into a contact frame More...
 
function obj = setReference (CoordinateFrame ref)
 set the reference frame More...
 
function obj = setOffset (rowvec offset)
 set the offset of the origin of the frame from the reference frame origin (in the reference frame) More...
 
function obj = setRotationMatrix (rowvec|matrix r)
 set the rotation matrix (R) of the frame w.r.t to the reference frame More...
 
function obj = computeHomogeneousTransform ()
 computes the homogeneous transformation matrix from the world coordinates More...
 
function pos = computeCartesianPosition (rowvec p)
 computes the cartesian position of a point p in the body (current) coordinate frame More...
 
function rpy = computeEulerAngle ()
 computes the Euler angles the body (current) coordinate frame in the world frame (base coordinate) More...
 
function g = computeForwardKinematics ()
 computes the forward kinematics transformation matrix of the coordinate frame More...
 
function Jac = computeBodyJacobian (integer nDof)
 computes the body Jacobian matrix of the coordinate frame More...
 
function Jac = computeSpatialJacobian (integer nDof)
 computes the spatial Jacobian matrix of the coordinate frame More...
 
function c_str = getTwists (matrix p)
 Returns the symbolic representation of the body jacobians of coordinate frames. More...
 

Public Attributes

char Type
 The type of the rigid joint. More...
 
rowvec Axis
 The rotation axis vector of the rigid joint. More...
 
char Child
 The name of the child link. More...
 
char Parent
 The name of the parent link. More...
 
struct Limit
 A structure data stores the physical limits of the rigid joints. More...
 
struct Actuator
 A structure contains information about the actuator for the joint. More...
 
rowvec ChainIndices
 The indices of kinematic chains from the base to the current joint. More...
 
rowvec Twist
 The twist from the base frame. More...
 
SymExpression TwistPairs
 The twist pairs of all precedent joints (coordinate frame) More...
 
- Public Attributes inherited from CoordinateFrame
char Name
 The name of the coordinate frame. More...
 
CoordinateFrame Reference
 The parent reference coordinate frame. More...
 
rowvec Offset
 The offset of the origin of the frame from the origin of the reference frame. More...
 
matrix R
 The rotation matrix of the frame w.r.t. the reference frame. More...
 
matrix gst0
 The homogeneous transformation from the base coordinate. More...
 
- Public Attributes inherited from handle
 addlistener
 Creates a listener for the specified event and assigns a callback function to execute when the event occurs. More...
 
 notify
 Broadcast a notice that a specific event is occurring on a specified handle object or array of handle objects. More...
 
 delete
 Handle object destructor method that is called when the object's lifecycle ends. More...
 
 disp
 Handle object disp method which is called by the display method. See the MATLAB disp function. More...
 
 display
 Handle object display method called when MATLAB software interprets an expression returning a handle object that is not terminated by a semicolon. See the MATLAB display function. More...
 
 findobj
 Finds objects matching the specified conditions from the input array of handle objects. More...
 
 findprop
 Returns a meta.property objects associated with the specified property name. More...
 
 fields
 Returns a cell array of string containing the names of public properties. More...
 
 fieldnames
 Returns a cell array of string containing the names of public properties. See the MATLAB fieldnames function. More...
 
 isvalid
 Returns a logical array in which elements are true if the corresponding elements in the input array are valid handles. This method is Sealed so you cannot override it in a handle subclass. More...
 
 eq
 Relational functions example. See details for more information. More...
 
 transpose
 Transposes the elements of the handle object array. More...
 
 permute
 Rearranges the dimensions of the handle object array. See the MATLAB permute function. More...
 
 reshape
 hanges the dimensions of the handle object array to the specified dimensions. See the MATLAB reshape function. More...
 
 sort
 ort the handle objects in any array in ascending or descending order. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from CoordinateFrame
static function gst = RPToHomogeneous (R, p)
 Convert a rotation + translation to a homogeneous matrix. More...
 
static function adj = RigidAdjoint (g)
 rigid adjoint matrix from the homonegeous matrix More...
 
static function RRigidOrientation (g)
 extract the rigid orientation from the homogeneous transformation matrix More...
 
static function p = RigidPosition (g)
 extract the rigid position from the homogeneous transformation matrix More...
 
static function s = AxisToSkew (p)
 converts the axis vector to a skew matrix More...
 

Detailed Description

A coordinate frame that is rigidly attached to the origin a rigid joint and the child link of the joint. In addition, this class stores the type, rotation axis, child link, and limit of the rigid joints.

Copyright (c) 2016-2017, AMBER Lab All right reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted only in compliance with the BSD 3-Clause license, see http://www.opensource.org/licenses/bsd-license.php

Constructor & Destructor Documentation

◆ RigidJoint()

RigidJoint.RigidJoint (   varargin)
inline

The class constructor function.

Parameters
vararginvariable nama-value pair input arguments, in detail: Required Parameters for varargin:
  • Name the name of the frame
  • Reference the reference frame
  • Offset the offset of the origin
  • R the rotation matrix or the Euler angles
  • Axis the rotation axis vector
  • Type the type of the joints
  • Child the child link frame
  • Limit the joint physical limits
Required fields of limit:
  • effort —  the maximum actuator effort
  • lower —  the minimum allowable displacement
  • upper —  the maximum allowable displacement
  • velocity —  the maximum allowable velocity

Member Function Documentation

◆ computeTwist()

function obj = RigidJoint.computeTwist ( )

computes the twist from the base frame

Generated fields of obj:

◆ getTwist()

function xi = RigidJoint.getTwist ( )

returns the twist vector of the rigid joint

◆ setActuator()

function obj = RigidJoint.setActuator (   varargin)

set the physical limits of the rigid joints

Parameters
vararginvaraiable input arguments. In detail:
setActuator ( [ "Inertia", Inertia_value ] [, "Ratio", Ratio_value ] )
Named Parameters for varargin:
  • Inertia the inertia of the actuator (before gear box) ( Default: [] )
  • Ratio the deceleration ratio of the gear box ( Default: [] )
Generated fields of obj:

◆ setAxis()

function obj = RigidJoint.setAxis ( rowvec  axis)

set the joint rotation axis vector in the joint coordinate

Parameters
axisthe axis vector
Generated fields of obj:

◆ setChainIndices()

function obj = RigidJoint.setChainIndices ( rowvec  indices)

Set the kinematic chain indices of the parent reference frames.

Parameters
indicesthe index vector
Generated fields of obj:

◆ setChild()

function obj = RigidJoint.setChild ( char  child)

set the child link frame

Parameters
childthe child link frame object
Generated fields of obj:

◆ setLimit()

function obj = RigidJoint.setLimit (   varargin)

set the physical limits of the rigid joints

Parameters
vararginvaraiable input arguments. In detail:
setLimit ( [ "effort", effort_value ] [, "lower", lower_value ]
[, "upper", upper_value ] [, "velocity", velocity_value ] )
Named Parameters for varargin:
  • effort the actuation effort ( Default: [] )
  • lower the lower bound of the joint displacement ( Default: [] )
  • upper the upper bound of the joint displacement ( Default: [] )
  • velocity the absolute bound of the joint velocity ( Default: [] )
Generated fields of obj:

◆ setParent()

function obj = RigidJoint.setParent ( char  parent)

set the parent link frame

Parameters
parentthe parent link frame object
Generated fields of obj:

◆ setTwistPairs()

function obj = RigidJoint.setTwistPairs ( RigitJoint  dofs,
SymVariable  q 
)

set the twist paris of all precedent joints

Parameters
dofsthe array of rigid joints
qthe symbolic variabls of rigid joints
Generated fields of obj:

◆ setType()

function obj = RigidJoint.setType ( char  type)

Sets the joint type.

Parameters
typethe joint type
Generated fields of obj:

Member Data Documentation

◆ Actuator

RigidJoint.Actuator

A structure contains information about the actuator for the joint.

An empty property indicates the joint is not actuated.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ Axis

RigidJoint.Axis

The rotation axis vector of the rigid joint.

Note
it must be a 3x1 vector.
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ ChainIndices

RigidJoint.ChainIndices

The indices of kinematic chains from the base to the current joint.

Note
This property has the MATLAB attribute Hidden set to true.
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ Child

RigidJoint.Child

The name of the child link.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ Limit

RigidJoint.Limit

A structure data stores the physical limits of the rigid joints.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ Parent

RigidJoint.Parent

The name of the parent link.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ Twist

RigidJoint.Twist

The twist from the base frame.

Note
This property has the MATLAB attribute Hidden set to true.
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ TwistPairs

RigidJoint.TwistPairs

The twist pairs of all precedent joints (coordinate frame)

Note
This property has the MATLAB attribute Hidden set to true.
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ Type

RigidJoint.Type

The type of the rigid joint.

Note
valid joint types include: revolute, prismatic, continuous, fixed.
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

The documentation for this class was generated from the following files:
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/RigidJoint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/computeTwist.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/getTwist.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setActuator.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setAxis.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setChainIndices.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setChild.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setLimit.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setParent.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setTwistPairs.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidJoint/setType.m