KrisLibrary  1.0.0
Public Member Functions | Public Attributes | List of all members
CartesianDriveSolver Class Reference

Simultaneously moves joints on the robot to achieve one or more Cartesian velocity goals. A highly configurable and reliable solver suitable for long-duration, precise cartesian motions. More...

#include <CartesianDrive.h>

Public Member Functions

 CartesianDriveSolver (RobotDynamics3D *robot)
 
void Init (const Config &q, const std::vector< int > &links)
 
void Init (const Config &q, const std::vector< int > &links, const std::vector< Vector3 > &endEffectorPositions)
 Alternate init: special end effector offsets (aka Tool Center Points)
 
void Init (const Config &q, const std::vector< int > &links, const std::vector< int > &baseLinks, const std::vector< Vector3 > &endEffectorPositions)
 
void Init (const Config &q, int link)
 Convenience helper for one link.
 
void Init (const Config &q, int link, const Vector3 &endEffectorPosition)
 Convenience helper for one link.
 
Real Drive (const Config &qcur, const std::vector< Vector3 > &angVel, const std::vector< Vector3 > &vel, Real dt, Config &qnext)
 
Real Drive (const Config &qcur, const Vector3 &angVel, const Vector3 &vel, Real dt, Config &qout)
 Convenience helper for one link.
 
void GetTrajectory (const Config &qcur, const std::vector< Vector3 > &angVel, const std::vector< Vector3 > &vel, Real dt, int numSteps, std::vector< Config > &trace, bool reset=true)
 

Public Attributes

RobotDynamics3Drobot
 
Real positionTolerance
 IK will maintained up to these tolerances. Default 1e-3.
 
Real rotationTolerance
 
Real ikSolveTolerance
 
int ikSolveIters
 IK solver will terminate when the solver meets this number of iterations.
 
std::vector< int > links
 The set of constrained links.
 
std::vector< int > baseLinks
 In relative cartesian positioning mode, these are the base links.
 
std::vector< Vector3endEffectorOffsets
 The set of end effector offsets.
 
std::vector< RigidTransformdriveTransforms
 The current cartesian drive goals. Must be of size links.size().
 
Real driveSpeedAdjustment
 If the IK solver had problems, the drive speed will be reduced.
 
std::vector< IKGoalikGoals
 
std::vector< int > activeDofs
 
Config qmin
 If set, overrides the robot's default joint limits.
 
Config qmax
 
Vector vmin
 If set, overrides the robot's default velocity limits.
 
Vector vmax
 

Detailed Description

Simultaneously moves joints on the robot to achieve one or more Cartesian velocity goals. A highly configurable and reliable solver suitable for long-duration, precise cartesian motions.

Most of the solver is stateless except for driveTransforms and driveSpeedAdjustment.

Member Function Documentation

Real CartesianDriveSolver::Drive ( const Config qcur,
const std::vector< Vector3 > &  angVel,
const std::vector< Vector3 > &  vel,
Real  dt,
Config qnext 
)

Given start configuration qcur, and desired angular/linear velocities of each link, drives the robot by time step dt to reach those cartesian goals. qnext is the resulting configuration, and the result is a value from 0 to 1 indicating how far along the nominal drive amount the solver was able to achieve. If the result is < 0, this indicates that the solver failed to make further progress.

For longer moves, you should pass qnext back to this function as qcur.

Hint: set angVel[i] infinite/NaN to turn off orientation control of constraint i.

Hint: set vel[i] infinite/Nan to turn off position control of constraint i.

limit the joint movement by joint limits and velocity

References AxisRotationMagnitude(), Math::Clamp(), GetDefaultIKDofs(), Math::IsFinite(), and NormalizeRotation().

void CartesianDriveSolver::GetTrajectory ( const Config qcur,
const std::vector< Vector3 > &  angVel,
const std::vector< Vector3 > &  vel,
Real  dt,
int  numSteps,
std::vector< Config > &  trace,
bool  reset = true 
)

Retrieves an entire trajectory produces by stepping numSteps steps at resolution dt.

If reset is true (on by default), resets the driveTransforms and driveSpeedAdjustment to the initial state after the trajectory is computed

void CartesianDriveSolver::Init ( const Config q,
const std::vector< int > &  links 
)

To start: call Init with the desired driven links. Then set up any additional settings for the IK solver (ikGoals, activeDofs, qmin, qmax, vmin, vmax). Then call Drive() each time you to update the drive commands.

void CartesianDriveSolver::Init ( const Config q,
const std::vector< int > &  links,
const std::vector< int > &  baseLinks,
const std::vector< Vector3 > &  endEffectorPositions 
)

Alternate init: relative positioning mode. Each link has a baseLink by which their cartesian movement is measured.

Member Data Documentation

std::vector<int> CartesianDriveSolver::activeDofs

If not set, uses default IK dofs. If set, these are the indices to be updated in Klampt

std::vector<IKGoal> CartesianDriveSolver::ikGoals

If set, must be of size links.size(). The driver updates the end effector DOFs selected for by these goals. If not set, uses fixed position/orientation goals.

Real CartesianDriveSolver::ikSolveTolerance

IK solver will terminate when the solver meets this tolerance. If 0, the tolerance will be determined from positionTolerance and rotationTolerance.


The documentation for this class was generated from the following files: