Klamp't  0.9.0
Files | Classes | Functions
Modeling

Files

file  RandomizedSelfCollisions.h
 Helper functions for computing potentially colliding pairs of links using random sampling.
 
file  Resources.h
 Defines all Klampt Resource types, and packing / unpacking utilities.
 
file  World.h
 Defines the WorldModel class.
 

Classes

class  Klampt::GeneralizedRobotModel
 A collection of robots and objects that can be treated like one "big robot". More...
 
class  Klampt::ManagedGeometry
 A "smart" geometry loading class that caches previous geometries and maintains shared collision detection / appearance information. This greatly speeds up loading time if multiple instances of the same geometry are loaded from disk, because multiple ManagedGeometry objects can share the same underlying data. It can also read from dynamic geometry sources (ROS point cloud topics, for now). More...
 
class  Klampt::MultiPath
 A very general multi-section path container. More...
 
class  Klampt::LinearPath
 A piecewise linear path. More...
 
class  Klampt::ConfigsResource
 Resource for multiple Config's. More...
 
class  Klampt::TriMeshResource
 Resource for a TriMesh. Needs to be overloaded to load from alternate mesh formats (meshing/IO.h). More...
 
class  Klampt::PointCloudResource
 Resource for a PointCloud3D. More...
 
class  Klampt::RobotResource
 Resource for a Robot. More...
 
class  Klampt::RigidObjectResource
 Resource for a RigidObject. More...
 
class  Klampt::WorldResource
 Resource for a WorldModel. More...
 
class  Klampt::LinearPathResource
 Resource for a LinearPath. More...
 
class  Klampt::MultiPathResource
 Resource for a MultiPath. More...
 
class  Klampt::IKGoalResource
 Resource for an IKGoal. More...
 
class  Klampt::HoldResource
 Resource for a Hold. More...
 
class  Klampt::StanceResource
 Resource for a Stance. More...
 
class  Klampt::GraspResource
 Resource for a Grasp. More...
 
class  Klampt::RigidObjectModel
 A (static) rigid object that may be manipulated. More...
 
struct  Klampt::RobotModelJoint
 Additional joint properties. More...
 
struct  Klampt::RobotModelDriver
 Determines the effects of an actuator on the robot configuration. More...
 
class  Klampt::RobotModel
 The main robot type used in RobotSim. More...
 
class  Klampt::TerrainModel
 A model of a static terrain with known friction. More...
 
class  Klampt::WorldModel
 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 Klampt::Interpolate (RobotModel &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 Klampt::InterpolateDerivative (RobotModel &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 Klampt::InterpolateDerivative (RobotModel &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 Klampt::Integrate (RobotModel &robot, const Config &q, const Vector &dq, Config &b)
 Integrates a velocity vector dq from q to obtain the configuration b.
 
Real Klampt::Distance (const RobotModel &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 Klampt::Distance (const RobotModel &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 Klampt::CenterOfMass (const Meshing::TriMesh &mesh, Real surfaceFraction=1.0)
 
Vector3 Klampt::CenterOfMass (const Meshing::PointCloud3D &pc, Real surfaceFraction=1.0)
 Computes the first moment integrated over the point cloud.
 
Vector3 Klampt::CenterOfMass (const Meshing::VolumeGrid &grid, Real surfaceFraction=1.0)
 
Vector3 Klampt::CenterOfMass (const Geometry::AnyGeometry3D &geom, Real surfaceFraction=1.0)
 Computes the first moment integrated over the geometry.
 
Matrix3 Klampt::Covariance (const Meshing::TriMesh &mesh, const Vector3 &center, Real surfaceFraction=1.0)
 Computes the second moment integrated over the geometry.
 
Matrix3 Klampt::Covariance (const Meshing::PointCloud3D &pc, const Vector3 &center, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Covariance (const Meshing::VolumeGrid &vol, const Vector3 &center, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Covariance (const Geometry::AnyGeometry3D &geom, const Vector3 &center, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Covariance (const Meshing::TriMesh &mesh, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Covariance (const Meshing::PointCloud3D &mesh, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Covariance (const Meshing::VolumeGrid &mesh, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Covariance (const Geometry::AnyGeometry3D &mesh, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Inertia (const Meshing::TriMesh &mesh, const Vector3 &center, Real mass, Real surfaceFraction=1.0)
 Computes the inertia tensor by integrating over the mesh.
 
Matrix3 Klampt::Inertia (const Meshing::PointCloud3D &mesh, const Vector3 &center, Real mass, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Inertia (const Meshing::VolumeGrid &mesh, const Vector3 &center, Real mass, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Inertia (const Geometry::AnyGeometry3D &mesh, const Vector3 &center, Real mass, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Inertia (const Meshing::TriMesh &mesh, Real mass, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Inertia (const Meshing::PointCloud3D &mesh, Real mass, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Inertia (const Meshing::VolumeGrid &mesh, Real mass, Real surfaceFraction=1.0)
 
Matrix3 Klampt::Inertia (const Geometry::AnyGeometry3D &mesh, Real mass, Real surfaceFraction=1.0)
 
Vector3 Klampt::CenterOfMass_Solid (const Meshing::TriMesh &mesh, Real gridRes)
 
Matrix3 Klampt::Covariance_Solid (const Meshing::TriMesh &mesh, Real gridRes, const Vector3 &center)
 
Matrix3 Klampt::Covariance_Solid (const Meshing::TriMesh &mesh, Real gridRes)
 
Matrix3 Klampt::Inertia_Solid (const Meshing::TriMesh &mesh, Real gridRes, const Vector3 &center, Real mass)
 
Matrix3 Klampt::Inertia_Solid (const Meshing::TriMesh &mesh, Real gridRes, Real mass)
 
void Klampt::Convert (const LinearPath &in, MultiPath &out)
 Exact, direct conversion from LinearPath to MultiPath.
 
void Klampt::Convert (const LinearPath &in, ParabolicRamp::DynamicPath &out)
 
void Klampt::Convert (const LinearPath &in, Spline::PiecewisePolynomialND &out)
 
void Klampt::Convert (const MultiPath &in, LinearPath &out)
 
void Klampt::Convert (const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
void Klampt::Convert (const MultiPath &in, Spline::PiecewisePolynomialND &out)
 
void Klampt::Convert (const ParabolicRamp::DynamicPath &in, MultiPath &out)
 Exact, direct conversion from DynamicPath to MultiPath.
 
void Klampt::Convert (const ParabolicRamp::DynamicPath &in, Spline::PiecewisePolynomialND &out)
 Exact, direct conversion from DynamicPath to PiecewisePolynomial.
 
void Klampt::Convert (const Spline::PiecewisePolynomialND &in, MultiPath &out)
 
void Klampt::Keyframes (const LinearPath &in, vector< Config > &milestones)
 Extract keyframes from the path representation.
 
void Klampt::Keyframes (const LinearPath &in, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::Keyframes (const LinearPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 Extracts keyframes + tangent vectors. Will construct tangent vectors by smoothing.
 
void Klampt::Keyframes (RobotModel &robot, const LinearPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Klampt::Keyframes (const MultiPath &in, vector< Config > &milestones)
 
void Klampt::Keyframes (const MultiPath &in, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::Keyframes (const MultiPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Klampt::Keyframes (RobotModel &robot, const MultiPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Klampt::Keyframes (const ParabolicRamp::DynamicPath &in, vector< Config > &milestones)
 
void Klampt::Keyframes (const ParabolicRamp::DynamicPath &in, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::Keyframes (const ParabolicRamp::DynamicPath &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Klampt::Keyframes (const Spline::PiecewisePolynomialND &in, vector< Config > &milestones)
 
void Klampt::Keyframes (const Spline::PiecewisePolynomialND &in, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::Keyframes (const Spline::PiecewisePolynomialND &in, vector< Real > &times, vector< Config > &milestones, vector< Config > &dmilestones)
 
void Klampt::Interpolate (const vector< Real > &times, const vector< Config > &milestones, LinearPath &out)
 Create a representation that matches the input keyframes.
 
void Klampt::Interpolate (const vector< Real > &times, const vector< Config > &milestones, MultiPath &out)
 Create a representation that matches the input keyframes.
 
void Klampt::Interpolate (const vector< Real > &times, const vector< Config > &milestones, Spline::PiecewisePolynomialND &out)
 
void Klampt::Interpolate (const vector< Real > &times, const vector< Config > &milestones, ParabolicRamp::DynamicPath &out)
 
void Klampt::Interpolate (const vector< Real > &times, const vector< Config > &milestones, const vector< Vector > &dmilestones, MultiPath &out)
 Create a representation that matches the input keyframes.
 
void Klampt::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 Klampt::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 Klampt::Interpolate (const LinearPath &in, T &out)
 Create a representation that matches the keyframes of the input path.
 
void Klampt::Interpolate (const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
void Klampt::Interpolate (const MultiPath &in, Spline::PiecewisePolynomialND &out)
 
void Klampt::Interpolate (const ParabolicRamp::DynamicPath &in, MultiPath &out)
 Create a representation that matches the keyframes of the input path.
 
template<class T >
void Klampt::Smooth (const LinearPath &in, T &out)
 
template<class T >
void Klampt::Smooth (const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
template<class T >
void Klampt::Smooth (RobotModel &robot, const LinearPath &in, T &out)
 
template<class T >
void Klampt::Smooth (RobotModel &robot, const MultiPath &in, ParabolicRamp::DynamicPath &out)
 
void Klampt::Discretize (const LinearPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 Split up the path into keyframes at a given resolution.
 
void Klampt::Discretize (const MultiPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::Discretize (const ParabolicRamp::DynamicPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::Discretize (const Spline::PiecewisePolynomialND &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::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 Klampt::Discretize (const MultiPath &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
void Klampt::Discretize (const ParabolicRamp::DynamicPath &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
void Klampt::Discretize (const Spline::PiecewisePolynomialND &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
void Klampt::Discretize (RobotModel &robot, const LinearPath &in, Real res, vector< Real > &times, vector< Config > &milestones)
 
void Klampt::Discretize (RobotModel &robot, const LinearPath &in, Real res, vector< Real > &times, vector< Config > &milestones, vector< Vector > &dmilestones)
 
template<class T1 , class T2 >
void Klampt::Approximate (const T1 &in, Real res, T2 &out)
 
template<class T1 >
void Klampt::Approximate (const T1 &in, Real res, LinearPath &out)
 
void Klampt::RandomizedSelfCollisionPairs (RobotWithGeometry &robot, Array2D< bool > &collision, int numSamples)
 Calculates a bit-matrix of potential collision pairs using random sampling. More...
 
void Klampt::RandomizedIndependentSelfCollisionPairs (RobotWithGeometry &robot, Array2D< bool > &collision, int numSamples)
 Calculates the bit-matrix of potential independent collision pairs. More...
 
void Klampt::RandomizedSelfCollisionDistances (RobotWithGeometry &robot, Array2D< Real > &minDistance, Array2D< Real > &maxDistance, int numSamples)
 Calculates the min/max distance matrix of collision pairs. More...
 
void Klampt::MakeRobotResourceLibrary (ResourceLibrary &library)
 Initializes a ResourceLibrary so that it accepts standard RobotSim file types.
 
ResourcePtr Klampt::MakeResource (const string &name, const vector< int > &vals)
 
ResourcePtr Klampt::MakeResource (const string &name, const vector< double > &vals)
 
ResourcePtr Klampt::MakeResource (const string &name, const Config &q)
 
ResourcePtr Klampt::MakeResource (const string &name, const vector< Config > &qs)
 
ResourcePtr Klampt::MakeResource (const string &name, const vector< Real > &ts, const vector< Config > &qs)
 
ResourcePtr Klampt::MakeResource (const string &name, const MultiPath &path)
 
ResourcePtr Klampt::MakeResource (const string &name, const Vector3 &pt)
 
ResourcePtr Klampt::MakeResource (const string &name, const Matrix3 &R)
 
ResourcePtr Klampt::MakeResource (const string &name, const RigidTransform &T)
 
ResourcePtr Klampt::MakeResource (const string &name, const GeometricPrimitive3D &geom)
 
ResourcePtr Klampt::MakeResource (const string &name, const Meshing::TriMesh &mesh)
 
ResourcePtr Klampt::MakeResource (const string &name, const Geometry::AnyGeometry3D &geom)
 
ResourcePtr Klampt::MakeResource (const string &name, const IKGoal &goal)
 
ResourcePtr Klampt::MakeResource (const string &name, const Hold &hold)
 
ResourcePtr Klampt::MakeResource (const string &name, const Stance &stance)
 
ResourcePtr Klampt::MakeResource (const string &name, const Grasp &grasp)
 
bool Klampt::CanCastResource (const ResourcePtr &item, const char *type)
 Returns true if CastResource can cast to the given type.
 
vector< string > Klampt::CastResourceTypes (const ResourcePtr &item)
 Returns the list of types which the item is castable to.
 
ResourcePtr Klampt::CastResource (ResourcePtr &item, const char *type)
 Convert a resource to a given type.
 
vector< string > Klampt::ExtractResourceTypes (const ResourcePtr &item)
 Returns the list of types that can be extracted from the item.
 
vector< ResourcePtr > Klampt::ExtractResources (ResourcePtr &item, const char *type)
 Extract all sub-resources of a given type.
 
ResourcePtr Klampt::PackResources (vector< ResourcePtr > &resources, ResourcePtr rtemplate, string *errorMessage=NULL)
 
ResourcePtr Klampt::PackResources (ResourceLibrary &resources, const string &type, string *errorMessage=NULL)
 Creates an object of the given type out of the given resources.
 
vector< ResourcePtr > Klampt::UnpackResource (ResourcePtr r, bool *successful=NULL, bool *incomplete=NULL)
 
void Klampt::SplineInterpolate (const vector< Vector > &pts, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 
void Klampt::SplineInterpolate (const vector< Vector > &pts, GeneralizedCubicBezierSpline &path, CSpace *space=NULL, GeodesicSpace *manifold=NULL, Real coxDeBoorParameter=0)
 
void Klampt::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 Klampt::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 Klampt::MonotonicInterpolate (const vector< Vector > &pts, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 
void Klampt::MonotonicInterpolate (const vector< Vector > &pts, GeneralizedCubicBezierSpline &path, CSpace *space=NULL, GeodesicSpace *manifold=NULL, Real coxDeBoorParameter=0)
 
void Klampt::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 Klampt::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 Klampt::MonotonicAccelInterpolate (const vector< Vector > &pts, vector< GeneralizedCubicBezierCurve > &paths, CSpace *space=NULL, GeodesicSpace *manifold=NULL)
 

Detailed Description

Function Documentation

template<class T1 , class T2 >
void Klampt::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 Klampt::Interpolate().

template<class T1 >
void Klampt::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 Klampt::Interpolate().

Vector3 Klampt::CenterOfMass ( const Meshing::TriMesh &  mesh,
Real  surfaceFraction = 1.0 
)

Computes the first moment integrated over the mesh. surfaceFraction indicates how much of the mass is concentrated at mesh considered as a hollow shell vs a solid.

Vector3 Klampt::CenterOfMass ( const Meshing::VolumeGrid &  grid,
Real  surfaceFraction = 1.0 
)

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

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

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

void Klampt::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 Klampt::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 Klampt::Convert ( const MultiPath in,
LinearPath out 
)

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

void Klampt::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 Klampt::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 Klampt::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.

Referenced by Klampt::LinearPath::Clear().

Matrix3 Klampt::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 Klampt::Discretize ( RobotModel 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 Klampt::Distance ( const RobotModel 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 Klampt::Distance ( const RobotModel 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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::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 Klampt::Smooth ( const LinearPath in,
T &  out 
)

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

References Klampt::Discretize(), Klampt::Interpolate(), and Klampt::Smooth().

Referenced by Klampt::Smooth().

void Klampt::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 Klampt::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> Klampt::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.