Klamp't  0.8.1
Files | Classes | Functions
Modeling

Files

file  RandomizedSelfCollisions.h
 Helper functions for computing potentially colliding pairs of links using random sampling.
 

Classes

class  GeneralizedRobot
 A collection of robots and objects that can be treated like one "big robot". More...
 
class  ManagedGeometry
 A "smart" geometry loading class that caches previous geometries, and does not re-load or re-initialize existing collision detection data structures if the item has already been loaded. More...
 
class  MultiPath
 A very general multi-section path container. More...
 
class  LinearPath
 A piecewise linear path. More...
 
class  ConfigsResource
 Resource for multiple Config's. More...
 
class  TriMeshResource
 Resource for a TriMesh. Needs to be overloaded to load from alternate mesh formats (meshing/IO.h). More...
 
class  PointCloudResource
 Resource for a PointCloud3D. More...
 
class  RobotResource
 Resource for a Robot. More...
 
class  RigidObjectResource
 Resource for a RigidObject. More...
 
class  WorldResource
 Resource for a RobotWorld. More...
 
class  LinearPathResource
 Resource for a LinearPath. More...
 
class  MultiPathResource
 Resource for a MultiPath. More...
 
class  IKGoalResource
 Resource for an IKGoal. More...
 
class  HoldResource
 Resource for a Hold. More...
 
class  StanceResource
 Resource for a Stance. More...
 
class  GraspResource
 Resource for a Grasp. More...
 
class  RigidObject
 A (static) rigid object that may be manipulated. More...
 
struct  RobotJoint
 Additional joint properties. More...
 
struct  RobotJointDriver
 Determines the effects of an actuator on the robot configuration. More...
 
class  Robot
 The main robot type used in RobotSim. More...
 
class  Terrain
 A model of a static terrain with known friction. More...
 
class  RobotWorld
 The main world class containing multiple robots, objects, and static geometries (terrains). Lights and other viewport information may also be stored here. More...
 

Functions

void Interpolate (Robot &robot, const Config &x, const Config &y, Real u, Config &out)
 Interpolates between the two configurations in geodesic fashion on the robot's underlying configuration space.
 
void InterpolateDerivative (Robot &robot, const Config &a, const Config &b, Vector &dq)
 Returns the velocity vector at a that will move the robot from a to b in minimal time (i.e., derivative of the geodesic).
 
void InterpolateDerivative (Robot &robot, const Config &a, const Config &b, Real u, Vector &dq)
 Returns the velocity vector that will move the robot from the configuration that is u fraction of the way from a to b to b in minimal time.
 
void Integrate (Robot &robot, const Config &q, const Vector &dq, Config &b)
 Integrates a velocity vector dq from q to obtain the configuration b.
 
Real Distance (const Robot &robot, const Config &a, const Config &b, Real norm, Real floatingRotationWeight=1.0)
 Returns the geodesic distance between a and b. Combines individual joint distances together via the L-k norm, where k = #norm. More...
 
Real Distance (const Robot &robot, const Config &a, const Config &b, Real norm, const vector< Real > &weights, Real floatingRotationWeight=1.0)
 Returns the geodesic distance between a and b. Combines individual joint distances together via the weighted L-k norm, where k = #norm. More...
 
Vector3 CenterOfMass (const Meshing::TriMesh &mesh)
 
Vector3 CenterOfMass (const Meshing::PointCloud3D &pc)
 Computes the first moment integrated over the point cloud.
 
Vector3 CenterOfMass (const Meshing::VolumeGrid &grid)
 
Vector3 CenterOfMass (const Geometry::AnyGeometry3D &geom)
 Computes the first moment integrated over the geometry.
 
Matrix3 Covariance (const Meshing::TriMesh &mesh, const Vector3 &center)
 Computes the second moment integrated over the geometry.
 
Matrix3 Covariance (const Meshing::PointCloud3D &pc, const Vector3 &center)
 
Matrix3 Covariance (const Meshing::VolumeGrid &vol, const Vector3 &center)
 
Matrix3 Covariance (const Geometry::AnyGeometry3D &geom, const Vector3 &center)
 
Matrix3 Covariance (const Meshing::TriMesh &mesh)
 
Matrix3 Covariance (const Meshing::PointCloud3D &mesh)
 
Matrix3 Covariance (const Meshing::VolumeGrid &mesh)
 
Matrix3 Covariance (const Geometry::AnyGeometry3D &mesh)
 
Matrix3 Inertia (const Meshing::TriMesh &mesh, const Vector3 &center, Real mass)
 Computes the inertia tensor by integrating over the mesh.
 
Matrix3 Inertia (const Meshing::PointCloud3D &mesh, const Vector3 &center, Real mass)
 
Matrix3 Inertia (const Meshing::VolumeGrid &mesh, const Vector3 &center, Real mass)
 
Matrix3 Inertia (const Geometry::AnyGeometry3D &mesh, const Vector3 &center, Real mass)
 
Matrix3 Inertia (const Meshing::TriMesh &mesh, Real mass)
 
Matrix3 Inertia (const Meshing::PointCloud3D &mesh, Real mass)
 
Matrix3 Inertia (const Meshing::VolumeGrid &mesh, Real mass)
 
Matrix3 Inertia (const Geometry::AnyGeometry3D &mesh, Real mass)
 
Vector3 CenterOfMass_Solid (const Meshing::TriMesh &mesh, Real gridRes)
 
Matrix3 Covariance_Solid (const Meshing::TriMesh &mesh, Real gridRes, const Vector3 &center)
 
Matrix3 Covariance_Solid (const Meshing::TriMesh &mesh, Real gridRes)
 
Matrix3 Inertia_Solid (const Meshing::TriMesh &mesh, Real gridRes, const Vector3 &center, Real mass)
 
Matrix3 Inertia_Solid (const Meshing::TriMesh &mesh, Real gridRes, Real mass)
 
void Convert (const LinearPath &in, MultiPath &out)
 Exact, direct conversion from LinearPath to MultiPath.
 
void Convert (const LinearPath &in, ParabolicRamp::DynamicPath &out)
 
void Convert (const LinearPath &in, Spline::PiecewisePolynomialND &out)
 
void Convert (const MultiPath &in, LinearPath &out)
 
void Convert (const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
void Convert (const MultiPath &in, Spline::PiecewisePolynomialND &out)
 
void Convert (const ParabolicRamp::DynamicPath &in, MultiPath &out)
 Exact, direct conversion from DynamicPath to MultiPath.
 
void Convert (const ParabolicRamp::DynamicPath &in, Spline::PiecewisePolynomialND &out)
 Exact, direct conversion from DynamicPath to PiecewisePolynomial.
 
void Convert (const Spline::PiecewisePolynomialND &in, MultiPath &out)
 
void Keyframes (const LinearPath &in, vector< Config > &milestones)
 Extract keyframes from the path representation.
 
void Keyframes (const LinearPath &in, vector< Real > &times, vector< Config > &milestones)
 
void Keyframes (const LinearPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 Extracts keyframes + tangent vectors. Will construct tangent vectors by smoothing.
 
void Keyframes (Robot &robot, const LinearPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Keyframes (const MultiPath &in, vector< Config > &milestones)
 
void Keyframes (const MultiPath &in, vector< Real > &times, vector< Config > &milestones)
 
void Keyframes (const MultiPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Keyframes (Robot &robot, const MultiPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Keyframes (const ParabolicRamp::DynamicPath &in, vector< Config > &milestones)
 
void Keyframes (const ParabolicRamp::DynamicPath &in, vector< Real > &times, vector< Config > &milestones)
 
void Keyframes (const ParabolicRamp::DynamicPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Keyframes (const Spline::PiecewisePolynomialND &in, vector< Config > &milestones)
 
void Keyframes (const Spline::PiecewisePolynomialND &in, vector< Real > &times, vector< Config > &milestones)
 
void Keyframes (const Spline::PiecewisePolynomialND &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Interpolate (const vector< Real > &times, const vector< Config > &milestones, LinearPath &out)
 Create a representation that matches the input keyframes.
 
void Interpolate (const vector< Real > &times, const vector< Config > &milestones, MultiPath &out)
 Create a representation that matches the input keyframes.
 
void Interpolate (const vector< Real > &times, const vector< Config > &milestones, Spline::PiecewisePolynomialND &out)
 
void Interpolate (const vector< Real > &times, const vector< Config > &milestones, ParabolicRamp::DynamicPath &out)
 
void Interpolate (const vector< Real > &times, const vector< Config > &milestones, const vector< Vector > &dmilestones, MultiPath &out)
 Create a representation that matches the input keyframes.
 
void Interpolate (const vector< Real > &times, const vector< Config > &milestones, const vector< Vector > &dmilestones, Spline::PiecewisePolynomialND &out)
 Create a representation that matches the input keyframes.
 
void Interpolate (const vector< Real > &times, const vector< Config > &milestones, const vector< Vector > &dmilestones, ParabolicRamp::DynamicPath &out)
 Create a representation that matches the input keyframes.
 
template<class T >
void Interpolate (const LinearPath &in, T &out)
 Create a representation that matches the keyframes of the input path.
 
void Interpolate (const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
void Interpolate (const MultiPath &in, Spline::PiecewisePolynomialND &out)
 
void Interpolate (const ParabolicRamp::DynamicPath &in, MultiPath &out)
 Create a representation that matches the keyframes of the input path.
 
template<class T >
void Smooth (const LinearPath &in, T &out)
 
template<class T >
void Smooth (const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
template<class T >
void Smooth (Robot &robot, const LinearPath &in, T &out)
 
template<class T >
void Smooth (Robot &robot, const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
void Discretize (const LinearPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 Split up the path into keyframes at a given resolution.
 
void Discretize (const MultiPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Discretize (const ParabolicRamp::DynamicPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Discretize (const Spline::PiecewisePolynomialND &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Discretize (const LinearPath &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 Split up the path into keyframes and velocities at a given resolution.
 
void Discretize (const MultiPath &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
void Discretize (const ParabolicRamp::DynamicPath &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
void Discretize (const Spline::PiecewisePolynomialND &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
void Discretize (Robot &robot, const LinearPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Discretize (Robot &robot, const LinearPath &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
template<class T1 , class T2 >
void Approximate (const T1 &in, Real res, T2 &out)
 
template<class T1 >
void Approximate (const T1 &in, Real res, LinearPath &out)
 
void RandomizedSelfCollisionPairs (RobotWithGeometry &robot, Array2D< bool > &collision, int numSamples)
 Calculates a bit-matrix of potential collision pairs using random sampling. More...
 
void RandomizedIndependentSelfCollisionPairs (RobotWithGeometry &robot, Array2D< bool > &collision, int numSamples)
 Calculates the bit-matrix of potential independent collision pairs. More...
 
void RandomizedSelfCollisionDistances (RobotWithGeometry &robot, Array2D< Real > &minDistance, Array2D< Real > &maxDistance, int numSamples)
 Calculates the min/max distance matrix of collision pairs. More...
 
void MakeRobotResourceLibrary (ResourceLibrary &library)
 Initializes a ResourceLibrary so that it accepts standard RobotSim file types.
 
ResourcePtr MakeResource (const string &name, const vector< int > &vals)
 
ResourcePtr MakeResource (const string &name, const vector< double > &vals)
 
ResourcePtr MakeResource (const string &name, const Config &q)
 
ResourcePtr MakeResource (const string &name, const vector< Config > &qs)
 
ResourcePtr MakeResource (const string &name, const vector< Real > &ts, const vector< Config > &qs)
 
ResourcePtr MakeResource (const string &name, const MultiPath &path)
 
ResourcePtr MakeResource (const string &name, const Vector3 &pt)
 
ResourcePtr MakeResource (const string &name, const Matrix3 &R)
 
ResourcePtr MakeResource (const string &name, const RigidTransform &T)
 
ResourcePtr MakeResource (const string &name, const GeometricPrimitive3D &geom)
 
ResourcePtr MakeResource (const string &name, const Meshing::TriMesh &mesh)
 
ResourcePtr MakeResource (const string &name, const Geometry::AnyGeometry3D &geom)
 
ResourcePtr MakeResource (const string &name, const IKGoal &goal)
 
ResourcePtr MakeResource (const string &name, const Hold &hold)
 
ResourcePtr MakeResource (const string &name, const Stance &stance)
 
ResourcePtr MakeResource (const string &name, const Grasp &grasp)
 
bool CanCastResource (const ResourcePtr &item, const char *type)
 Returns true if CastResource can cast to the given type.
 
vector< string > CastResourceTypes (const ResourcePtr &item)
 Returns the list of types which the item is castable to.
 
ResourcePtr CastResource (ResourcePtr &item, const char *type)
 Convert a resource to a given type.
 
vector< string > ExtractResourceTypes (const ResourcePtr &item)
 Returns the list of types that can be extracted from the item.
 
vector< ResourcePtr > ExtractResources (ResourcePtr &item, const char *type)
 Extract all sub-resources of a given type.
 
ResourcePtr PackResources (vector< ResourcePtr > &resources, ResourcePtr rtemplate, string *errorMessage=NULL)
 
ResourcePtr PackResources (ResourceLibrary &resources, const string &type, string *errorMessage=NULL)
 Creates an object of the given type out of the given resources.
 
vector< ResourcePtr > UnpackResource (ResourcePtr r, bool *successful=NULL, bool *incomplete=NULL)
 
void SplineInterpolate (const vector< Vector > &pts, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 
void SplineInterpolate (const vector< Vector > &pts, GeneralizedCubicBezierSpline &path, CSpace *space=NULL, GeodesicSpace *manifold=NULL, Real coxDeBoorParameter=0)
 
void SplineInterpolate (const vector< Vector > &pts, const vector< Real > &times, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 Interpolates the given points at the given times.
 
void SplineInterpolate (const vector< Vector > &pts, const vector< Real > &times, GeneralizedCubicBezierSpline &path, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 Same as above but outputs a spline, sets the path's durations.
 
void MonotonicInterpolate (const vector< Vector > &pts, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 
void MonotonicInterpolate (const vector< Vector > &pts, GeneralizedCubicBezierSpline &path, CSpace *space=NULL, GeodesicSpace *manifold=NULL, Real coxDeBoorParameter=0)
 
void MonotonicInterpolate (const vector< Vector > &pts, const vector< Real > &times, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 Same as above but with times.
 
void MonotonicInterpolate (const vector< Vector > &pts, const vector< Real > &times, GeneralizedCubicBezierSpline &path, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 Same as above but outputs a spline, sets the path's durations.
 
void MonotonicAccelInterpolate (const vector< Vector > &pts, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 
void CopyWorld (const RobotWorld &a, RobotWorld &b)
 Performs a shallow copy of a RobotWorld. Since it does not copy geometry, this operation is very fast.
 

Detailed Description

Function Documentation

template<class T1 , class T2 >
void Approximate ( const T1 &  in,
Real  res,
T2 &  out 
)

Create a representation that matches the input path at keyframes derived from the path at a given resolution

References Discretize(), and Interpolate().

template<class T1 >
void Approximate ( const T1 &  in,
Real  res,
LinearPath out 
)

Create a representation that matches the input path at keyframes derived from the path at a given resolution

References Discretize(), and Interpolate().

Vector3 CenterOfMass ( const Meshing::TriMesh &  mesh)

Computes the first moment integrated over the mesh (assuming the mesh is a hollow shell)

Vector3 CenterOfMass ( const Meshing::VolumeGrid &  grid)

Computes the first moment integrated over the volume grid (assuming < 0 is the interior)

Vector3 CenterOfMass_Solid ( const Meshing::TriMesh &  mesh,
Real  gridRes 
)

Computes the first moment integrated over the solid inside the mesh using a grid approximation

void Convert ( const LinearPath in,
ParabolicRamp::DynamicPath out 
)

Exact, direct conversion from LinearPath to DynamicPath. Warning: discontinuous derivatives. Use Smooth to get a smooth path.

void Convert ( const LinearPath in,
Spline::PiecewisePolynomialND &  out 
)

Exact, direct conversion from LinearPath to PiecewisePolynomial. Warning: discontinuous derivatives. Use Smooth to get a smooth path.

void Convert ( const MultiPath in,
LinearPath out 
)

Exact, direct conversion from MultiPath to LinearPath. Input path must not have velocities.

void Convert ( const MultiPath in,
ParabolicRamp::DynamicPath out 
)

Exact, direct conversion from MultiPath to DynamicPath Warning: may have discontinuous derivatives if velocities not given. Use Smooth to get a smooth path.

void Convert ( const MultiPath in,
Spline::PiecewisePolynomialND &  out 
)

Exact, direct conversion from MultiPath to PiecewisePolynomial. Warning: may have discontinuous derivatives if velocities not given. Use Smooth to get a smooth path.

void Convert ( const Spline::PiecewisePolynomialND &  in,
MultiPath out 
)

Exact, direct conversion from PiecewisePolynomial to DynamicPath. Input path polynomials must have degree at most 2. Exact, direct conversion from PiecewisePolynomial to DynamicPath. Input path polynomials must have degree at most 3.

Matrix3 Covariance_Solid ( const Meshing::TriMesh &  mesh,
Real  gridRes,
const Vector3 &  center 
)

Computes the first moment integrated over the solid inside the mesh using a grid approximation

void Discretize ( Robot robot,
const LinearPath in,
Real  res,
vector< Real > &  times,
vector< Config > &  milestones 
)

Split up the path into keyframes and velocities at a given resolution using the robot interpolation function

Real Distance ( const Robot robot,
const Config &  a,
const Config &  b,
Real  norm,
Real  floatingRotationWeight = 1.0 
)

Returns the geodesic distance between a and b. Combines individual joint distances together via the L-k norm, where k = #norm.

For floating joints, the rotation error is multiplied by floatingRotationWeight

Real Distance ( const Robot robot,
const Config &  a,
const Config &  b,
Real  norm,
const vector< Real > &  weights,
Real  floatingRotationWeight = 1.0 
)

Returns the geodesic distance between a and b. Combines individual joint distances together via the weighted L-k norm, where k = #norm.

For floating joints, the rotation error is multiplied by floatingRotationWeight

Matrix3 Inertia_Solid ( const Meshing::TriMesh &  mesh,
Real  gridRes,
const Vector3 &  center,
Real  mass 
)

Computes the inertia integrated over the solid inside the mesh using a grid approximation

void Interpolate ( const vector< Real > &  times,
const vector< Config > &  milestones,
Spline::PiecewisePolynomialND &  out 
)

Create a representation that matches the input keyframes. The path will be smooth and stop at each milestone with zero velocity.

void Interpolate ( const vector< Real > &  times,
const vector< Config > &  milestones,
ParabolicRamp::DynamicPath out 
)

Create a representation that matches the input keyframes. The path will be smooth and will stop at each milestone with zero velocity.

void Interpolate ( const MultiPath in,
ParabolicRamp::DynamicPath out 
)

Create a representation that matches the keyframes of the input path. The path will be smooth and if the input path has no velocities, the output will stop at each milestone with zero velocity

void Interpolate ( const MultiPath in,
Spline::PiecewisePolynomialND &  out 
)

Create a representation that matches the keyframes of the input path. The path will be smooth and if the input path has no velocities, the output will stop at each milestone with zero velocity

void MonotonicInterpolate ( const vector< Vector > &  pts,
vector< GeneralizedCubicBezierCurve > &  paths,
CSpace *  space = NULL,
GeodesicSpace *  manifold = NULL 
)

Interpolates ensuring that each intermediate segment is monotonically increasing / decreasing (potentially less oscillation). The resulting path segments are C1 continuous when connected via a uniform parameterization.

void MonotonicInterpolate ( const vector< Vector > &  pts,
GeneralizedCubicBezierSpline &  path,
CSpace *  space = NULL,
GeodesicSpace *  manifold = NULL,
Real  coxDeBoorParameter = 0 
)

Interpolates the given points using monotonic interpolation, returning a timed path. If coxDeBoorParameter = 0, then a uniform parameterization is used. If 1, then the distance between points is used to define the parametrization (chordal parameterization). If 0.5, the centripetal parametrization is/ used, which has some advantages.

ResourcePtr PackResources ( vector< ResourcePtr > &  resources,
ResourcePtr  rtemplate,
string *  errorMessage = NULL 
)

Creates an object of the same type as the template out of the given resources

void RandomizedIndependentSelfCollisionPairs ( RobotWithGeometry &  robot,
Array2D< bool > &  collision,
int  numSamples 
)

Calculates the bit-matrix of potential independent collision pairs.

Sets collision(i,j) = true iff a collision between link i and j has been detected within numSamples samples. And independent means they have been detected to occur independently of any other pair.

void RandomizedSelfCollisionDistances ( RobotWithGeometry &  robot,
Array2D< Real > &  minDistance,
Array2D< Real > &  maxDistance,
int  numSamples 
)

Calculates the min/max distance matrix of collision pairs.

Sets min/maxDistance(i,j) to the min/max distance between bodies i and j within numSamples samples.

void RandomizedSelfCollisionPairs ( RobotWithGeometry &  robot,
Array2D< bool > &  collision,
int  numSamples 
)

Calculates a bit-matrix of potential collision pairs using random sampling.

Sets collision(i,j) = true iff a collision between link i and j has been detected within numSamples samples.

template<class T >
void Smooth ( const LinearPath in,
T &  out 
)

Create a representation that matches the input path at its given keyframes and imputed tangent vectors.

References Discretize(), Interpolate(), and Keyframes().

void SplineInterpolate ( const vector< Vector > &  pts,
vector< GeneralizedCubicBezierCurve > &  paths,
CSpace *  space = NULL,
GeodesicSpace *  manifold = NULL 
)

Interpolates the given points. The resulting path segments are C1 continuous when connected via a uniform parameterization.

void SplineInterpolate ( const vector< Vector > &  pts,
GeneralizedCubicBezierSpline &  path,
CSpace *  space = NULL,
GeodesicSpace *  manifold = NULL,
Real  coxDeBoorParameter = 0 
)

Interpolates the given points and returns a timed path. If coxDeBoorParameter = 0, then a uniform parameterization is used. If 1, then the distance between points is used to define the parametrization (chordal parameterization). If 0.5, the centripetal parametrization is used, which has some advantages.

vector<ResourcePtr> UnpackResource ( ResourcePtr  r,
bool *  successful = NULL,
bool *  incomplete = NULL 
)

Creates sub-objects from the given resource. If the decomposition succeeded, the flag successful is set to true. If the decomposition is incomplete, the flag incomplete is set to true. Here "incomplete" means that calling Pack on the return array will NOT produce a copy of r.