SCL  1.0
Standard Control Library : Control, dynamics, physics, and simulation
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Macros Groups Pages
Classes | Typedefs | Enumerations | Functions | Variables
scl Namespace Reference

Classes

class  SActuatorSettings
 
class  CActuatorBase
 
class  CActuatorSetBase
 
class  SActuatorSetBase
 
class  CActuatorMuscle
 
class  CActuatorSetMuscle
 
class  SActuatorMuscle
 
class  SActuatorSetMuscle
 
class  CControllerBase
 
class  SControllerBase
 
class  CControllerGc
 
class  SControllerGc
 
class  CControllerMultiTask
 
class  CNonControlTaskBase
 
class  CServo
 
class  CTaskBase
 
class  SControllerMultiTask
 
class  SNonControlTaskBase
 
class  SServo
 
class  STaskBase
 
class  CTaskComPos
 
class  CTaskGc
 
class  CTaskGcLimitCentering
 
class  CTaskGcSet
 
class  CTaskNULL
 
class  CTaskNullSpaceDamping
 
class  CTaskOpPos
 
class  CTaskOpPosContactForce
 
class  CTaskOpPosNoGravity
 
class  CTaskOpPosPIDA1OrderInfTime
 
class  STaskComPos
 
class  STaskGc
 
class  STaskGcLimitCentering
 
class  STaskGcSet
 
class  STaskNullSpaceDamping
 
class  STaskOpPos
 
class  STaskOpPosContactForce
 
class  STaskOpPosNoGravity
 
class  STaskOpPosPIDA1OrderInfTime
 
class  SMusclePointParsed
 
class  SMuscleParsed
 
class  SActuatorSetMuscleParsed
 
class  SActuatorSetParsed
 
struct  SParserData
 
class  SControllerData
 
struct  SGuiData
 
struct  SIOData
 
class  SDatabase
 
struct  SForce
 
struct  SForceContact
 
class  SGcModel
 
struct  SGraphicsParsed
 
class  SObject
 
class  SRigidBodyGraphics
 
struct  SRigidBody
 
class  SRigidBodyDyn
 
struct  SRobotSensors
 
struct  SRobotActuators
 
struct  SRobotIO
 
struct  SRobotParsed
 
class  SUIParsed
 
class  SVirtualLinkage
 
struct  sFloat3
 
struct  sString2
 
class  CDynamicsAnalyticRPP
 
class  CDynamicsAnalyticBase
 
class  CDynamicsBase
 
class  CDynamicsScl
 
class  CDynamicsTao
 
class  CTaoRepCreator
 
class  CGraphicsBase
 
class  CGraphicsChai
 
struct  SRobotRenderObj
 
class  SGraphicsChai
 
struct  SGraphicsChaiMuscleSet
 
struct  SGraphicsChaiRigidBody
 
struct  SGraphicsChaiMesh
 
class  CHapticsChai
 
class  CHapticsBase
 
class  CParserBase
 
class  CParserOsim
 
class  CParserOsimForOldFiles
 
class  CParserSai
 
class  STaskParsedData
 
class  SNonControlTaskParsedData
 
class  CParserScl
 
class  CParserSclTiXml
 
class  CRobot
 
class  CRobotApp
 
class  SRobot
 
class  CCallbackEcho
 
class  CCallbackPrint
 
class  CCallbackSet
 
class  CCallbackHelp
 
class  CCallbackDecrement
 
class  CCallbackIncrement
 
class  SSensorBase
 
class  CSensorBase
 
class  CSensorSetBase
 
class  CTrajectoryGenerator
 
class  CSimbodyDynamics
 

Typedefs

typedef bool sBool
 
typedef char sChar
 
typedef unsigned long sUInt
 
typedef int sInt
 
typedef long long sLongLong
 
typedef double sFloat
 
typedef double sClock
 
typedef Eigen::Matrix< sFloat, 6, 1 > sSpatialVector
 Typedef (possibly clearer to read). More...
 
typedef Eigen::Matrix< sFloat, 6, 6 > sSpatialXForm
 Typedef since we use this pretty commonly. More...
 
typedef sutil::CSingleton
< SDatabase
CDatabase
 
typedef sutil::CSingleton
< sutil::CMappedList
< std::string, SObject * > > 
CDatabaseDynObj
 

Enumerations

enum  EJointType {
  JOINT_TYPE_PRISMATIC_X = 0, JOINT_TYPE_PRISMATIC_Y = 1, JOINT_TYPE_PRISMATIC_Z = 2, JOINT_TYPE_REVOLUTE_X = 4,
  JOINT_TYPE_REVOLUTE_Y = 5, JOINT_TYPE_REVOLUTE_Z = 6, JOINT_TYPE_SPHERICAL = 8, JOINT_TYPE_SPLINE = 9,
  JOINT_TYPE_NOTASSIGNED = -1
}
 
enum  ERenderType { RENDER_TYPE_SPHERE = 0, RENDER_TYPE_CYLINDER = 1, RENDER_TYPE_ELLIPSOID = 2 }
 

Functions

static void tao_collect_ids (taoDNode *node, std::map< int, int > &id_counter)
 
static bool tao_consistency_check (taoNodeRoot *root)
 
bool addRobotPrintables ()
 
sBool sclTransform (Eigen::Affine3d &arg_T, const Eigen::Vector3d &arg_offset, const Eigen::Quaterniond &arg_ori_in_parent, const sFloat arg_q, const EJointType arg_jtype)
 
void dh2TransformationMatrix (Eigen::Matrix4d &arg_mat, const sFloat &alpha, const sFloat &a, const sFloat &d, const sFloat &theta)
 
sBool quat2axisangle (const Eigen::Quaternion< sFloat > &arg_q, Eigen::Vector4d &arg_aa)
 

Variables

const sFloat CHAI_SPHERE_RENDER_RADIUS = 0.0001
 
const sFloat CHAI_SPHERE_MUSC_VIA_RADIUS = 0.008
 
const sFloat CHAI_MUSC_THICKNESS = 10
 

Detailed Description

A singleton to unify all the disparate data sources in scl. Similar to a very fast database.

The data structure is universally available for any subcomponent of Scl to use.

A data structure to store the main servo loop's data. The main servo loop accesses the current torques to be applied from each task, computes the range spaces of the tasks and projects the torques through them to obtain the combined robot torque.

Typedef Documentation

Data structure wrapper which will contain all the data required to simulate and/or control a set of robots.

These classes will provide direct memory access to all the data stored within it.

TODO : Thread safety : 1-writer + n-readers for different subcomponents

Data structure wrapper which will contain all the data that a user might query during run time. This data will typically be accessed through callbacks.

typedef bool scl::sBool

Standard bool

typedef char scl::sChar

Standard char

typedef double scl::sClock

Clock (Can use system clock measurements which require more than a float

typedef double scl::sFloat

Standard floating point ops in general NOTE : Float is precise to 7 significant-digits This is fine for most scl ops.

typedef int scl::sInt

Standard int (4-byte)

typedef long long scl::sLongLong

Standard longlong

typedef Eigen::Matrix<sFloat, 6, 1> scl::sSpatialVector

Typedef (possibly clearer to read).

typedef Eigen::Matrix<sFloat, 6, 6> scl::sSpatialXForm

Typedef since we use this pretty commonly.

Enumeration Type Documentation

Enum for the different joint types in scl Note: Arbitrary joint axis rotations are not supported. You may instead rotate the transformation from the previous link's frame to go to a standard axis (x,y,z). It is best to just use z when you can (our convention).

Function Documentation

void scl::dh2TransformationMatrix ( Eigen::Matrix4d &  arg_mat,
const sFloat &  alpha,
const sFloat &  a,
const sFloat &  d,
const sFloat &  theta 
)

Creates a transformation matrix given a set of dh parameters z = axis or rotation. x = joint(i-1) to joint(i). y = z cross x SI units : radian, meters alpha : Angle about common normal (Z_n-1 to Z_n) a (or r) : Length of common normal (Z_n-1 to Z_n = radius) d : Offset along z to common normal theta : Angle about prev z, from old x to new x.

sBool scl::quat2axisangle ( const Eigen::Quaternion< sFloat > &  arg_q,
Eigen::Vector4d &  arg_aa 
)

Converts a quaternion into an axis-angle (x,y,z,theta) representation.

At axis-angle's two singularities (pi and 0), the passed vector4 will be set to all zeros.

angle = 2 * acos(qw) x = qx / sqrt(1-qw*qw) y = qy / sqrt(1-qw*qw) z = qz / sqrt(1-qw*qw)

http://www.euclideanspace.com/maths/geometry/rotations/ conversions/quaternionToAngle/index.htm

sBool scl::sclTransform ( Eigen::Affine3d &  arg_T,
const Eigen::Vector3d &  arg_offset,
const Eigen::Quaterniond &  arg_ori_in_parent,
const sFloat  arg_q,
const EJointType  arg_jtype 
)

Creates a transformation matrix from a given joint specification and a generalized coordinate.