A coordinate frame that is rigidly attached to the CoM position of a rigid link. In addition, this class also stores the mass and inertia of the rigid link to which the frame is attached. More...
Public Member Functions | |
RigidBody (varargin) | |
The class constructor function. More... | |
function obj = | setMass (double mass) |
sets the link mass More... | |
function obj = | setInertia (matrix inertia) |
sets the inertia (matrix) of the link 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 | |
double | Mass |
The mass of the rigid link. More... | |
matrix | Inertia |
The inertia of the rigid link. 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 R = | RigidOrientation (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 CoM position of a rigid link. In addition, this class also stores the mass and inertia of the rigid link to which the frame is attached.
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
◆ RigidBody()
|
inline |
The class constructor function.
- Parameters
-
varargin variable 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
- Mass the mass of the link
- Inertia the inertia of the link
Member Function Documentation
◆ setInertia()
function obj = RigidBody.setInertia | ( | matrix | inertia | ) |
sets the inertia (matrix) of the link
- Parameters
-
inertia the inertia matrix
- Generated fields of obj:
◆ setMass()
function obj = RigidBody.setMass | ( | double | mass | ) |
sets the link mass
- Parameters
-
mass the link mass
- Generated fields of obj:
Member Data Documentation
◆ Inertia
RigidBody.Inertia |
The inertia of the rigid link.
- Note
- This property has non-standard access specifiers:
SetAccess = Protected, GetAccess = Public
- Matlab documentation of property attributes.
◆ Mass
RigidBody.Mass |
The mass of the rigid link.
- Note
- 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/@RigidBody/RigidBody.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidBody/setInertia.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidBody/setMass.m