Robowflex  v0.1
Making MoveIt Easy
robowflex::darts::TSRSet Class Reference

Manager for a set of TSR constraints. Attempts to reduce redundancy and combines errors and Jacobians together. More...

#include <tsr.h>

Public Member Functions

void print (std::ostream &out) const
 Print out the TSRs in this set. More...
 
Constructor and Initialization
 TSRSet (const WorldPtr &world, const TSRPtr &tsr)
 Constructor. More...
 
 TSRSet (const WorldPtr &world, const std::vector< TSRPtr > &tsrs, bool intersect=true)
 Constructor. More...
 
void setWorld (const WorldPtr &world)
 Set the world used by this TSR set. More...
 
void addTSR (const TSRPtr &tsr, bool intersect=true, double weight=1.0)
 Add a TSR to the set. More...
 
void initialize ()
 Initialize this set of TSRs. More...
 
void updateSolver ()
 Update the solver information (iterations, tolerance, etc.) More...
 
DoF Indexing
void useGroup (const std::string &name)
 Use the joints in a robot's group. Robot used is the target frame's structure. More...
 
void useIndices (const std::vector< std::size_t > &indices)
 Use DoF indices for all TSRs computation. More...
 
void useWorldIndices (const std::vector< std::pair< std::size_t, std::size_t >> &indices)
 Use World DoF indices for all TSRs computation. World indices are pairs of skeleton index and DoF index. More...
 
void setWorldIndices (const std::vector< std::pair< std::size_t, std::size_t >> &indices)
 Output world indices. TSR information for *WorldState methods uses this set of world indices. World indices are pairs of skeleton index and DoF index. More...
 
const std::vector< std::pair< std::size_t, std::size_t > > & getWorldIndices () const
 Get the world indices used. More...
 
void setWorldUpperLimits (const Eigen::Ref< const Eigen::VectorXd > &upper)
 Set the upper limit on joints given their index in the world configuration. More...
 
void setWorldLowerLimits (const Eigen::Ref< const Eigen::VectorXd > &lower)
 Set the lower limit on joints given their index in the world configuration. More...
 
void computeLimits ()
 Compute the upper and lower limits from the skeleton. More...
 
Getters
void getPositionsWorldState (Eigen::Ref< Eigen::VectorXd > world) const
 Get the current world state. More...
 
std::size_t getDimension () const
 Get the error dimension of this set of TSRs. More...
 
std::size_t numTSRs () const
 Get the number of TSRs in the set. More...
 
const std::vector< TSRPtr > & getTSRs () const
 Get the TSRs that form the set. More...
 
double getTolerance () const
 Get the numerical tolerance for solving. More...
 
void setTolerance (double tolerance)
 Set the maximum tolerance used for solving. More...
 
std::size_t getMaxIterations () const
 Get the maximum iterations allowed. More...
 
void setMaxIterations (std::size_t iterations)
 Set the maximum iterations used for solving. More...
 
void addSuffix (const std::string &suffix)
 Add a suffix to the end of all structures in the TSRs in the set. More...
 
void setStep (double step)
 Set the step parameter in the solver. More...
 
double getStep () const
 Get the solver step parameter. More...
 
void setLimit (double limit)
 Set the limit parameter in the solver. More...
 
double getLimit () const
 Get the solver limit parameter. More...
 
void setDamping (double damping)
 Set the damping parameter in the solver. More...
 
double getDamping () const
 Get the solver damping parameter. More...
 
void useDamping (bool damping)
 Set if damping is used in SVD solving. More...
 
void useSVD ()
 Use SVD for solving. More...
 
void useQR ()
 Use QR for solving. More...
 
Error / Function Computation
void getErrorWorld (Eigen::Ref< Eigen::VectorXd > error) const
 Get the current error given the world state. More...
 
void getErrorWorldState (const Eigen::Ref< const Eigen::VectorXd > &world, Eigen::Ref< Eigen::VectorXd > error) const
 Get the error given a provided world configuration. More...
 
Jacobian Computation
void getJacobianWorldState (const Eigen::Ref< const Eigen::VectorXd > &world, Eigen::Ref< Eigen::MatrixXd > jacobian) const
 Get the Jacobian given a provided world configuration. More...
 
Distance Computation
double distanceWorld () const
 Get the current distance to satisfaction given the world state. More...
 
double distanceWorldState (const Eigen::Ref< const Eigen::VectorXd > &world) const
 Get the distance to satisfaction given a provided world configuration. More...
 
Solving for Satisfying Configurations
bool solveWorld ()
 Solve for a satisfying configuration given the current state of the world. More...
 
bool solveWorldState (Eigen::Ref< Eigen::VectorXd > world)
 Solve for a satisfying configuration given an initial world configuration. More...
 
bool solveGradientWorldState (Eigen::Ref< Eigen::VectorXd > world)
 Solve using gradient descent for a satisfying configuration given an initial world configuration. More...
 

Private Member Functions

void enforceBoundsWorld (Eigen::Ref< Eigen::VectorXd > world) const
 Enforce upper and lower bounds on a world configuration. More...
 

Private Attributes

WorldPtr world_
 World to use. More...
 
std::set< std::size_tskel_indices_
 All skeleton indices used by members of the set. More...
 
bool qr_ {false}
 If true, use QR in gradient solve. Else, SVD. More...
 
bool damped_ {true}
 If true, use damped SVD. More...
 
double step_ {1.0}
 Step scaling in gradient. More...
 
double limit_ {1.}
 Step size limit. More...
 
double damping_ {1e-8}
 Damping factor. More...
 
double tolerance_ {magic::DEFAULT_IK_TOLERANCE}
 Tolerance for solving. More...
 
std::size_t maxIter_ {50}
 Maximum iterations to use for solving. More...
 
std::vector< TSRPtrtsrs_
 Set of TSRs. More...
 
std::vector< double > weights_
 Weights on TSRs. More...
 
std::size_t dimension_ {0}
 Total error dimension of set. More...
 
Eigen::VectorXd upper_
 Upper bounds on world configuration. More...
 
Eigen::VectorXd lower_
 Lower bounds on world configuration. More...
 

Detailed Description

Manager for a set of TSR constraints. Attempts to reduce redundancy and combines errors and Jacobians together.

Will "stack" the error values and Jacobians together. For example, given two TSRs "a" and "b" in the set, the error vector will be [ea, eb] where ea and eb are a and b's error vector. The Jacobian will also correspond to this stacked error vector.

Definition at line 725 of file tsr.h.

Constructor & Destructor Documentation

◆ TSRSet() [1/2]

TSRSet::TSRSet ( const WorldPtr world,
const TSRPtr tsr 
)

Constructor.

Parameters
[in]worldWorld to use.
[in]tsrTSR to add to set.

TSRSet

Definition at line 928 of file tsr.cpp.

928  : world_(world)
929 {
930  addTSR(tsr);
931 }
WorldPtr world_
World to use.
Definition: tsr.h:983
void addTSR(const TSRPtr &tsr, bool intersect=true, double weight=1.0)
Add a TSR to the set.
Definition: tsr.cpp:939

◆ TSRSet() [2/2]

TSRSet::TSRSet ( const WorldPtr world,
const std::vector< TSRPtr > &  tsrs,
bool  intersect = true 
)

Constructor.

Parameters
[in]worldWorld to use.
[in]tsrsTSRs to add to set.
[in]intersectIf true, tries to simplify TSR set.

Definition at line 933 of file tsr.cpp.

933  : world_(world)
934 {
935  for (const auto &tsr : tsrs)
936  addTSR(tsr, intersect);
937 }

Member Function Documentation

◆ addSuffix()

void TSRSet::addSuffix ( const std::string suffix)

Add a suffix to the end of all structures in the TSRs in the set.

Parameters
[in]suffixSuffix to add.

Definition at line 992 of file tsr.cpp.

993 {
994  for (auto &tsr : tsrs_)
995  tsr->getSpecification().addSuffix(suffix);
996 }
std::vector< TSRPtr > tsrs_
Set of TSRs.
Definition: tsr.h:994

◆ addTSR()

void TSRSet::addTSR ( const TSRPtr tsr,
bool  intersect = true,
double  weight = 1.0 
)

Add a TSR to the set.

Parameters
[in]tsrTSR to add.
[in]intersectIf true, tries to simplify TSR set.
[in]weightWeight to use for this TSR.

Definition at line 939 of file tsr.cpp.

940 {
941  TSRPtr ntsr = tsr;
942  TSR::Specification spec = tsr->getSpecification();
943  if (intersect)
944  {
945  for (auto &etsr : tsrs_)
946  // Don't need this entire TSR if we can intersect
947  if (etsr->getSpecification().intersect(spec))
948  {
949  dimension_ = 0;
950  for (auto &tsr : tsrs_)
951  dimension_ += tsr->getDimension();
952  return;
953  }
954 
955  // copy for intersections later
956  ntsr = std::make_shared<TSR>(world_, spec);
957  ntsr->useIndices(tsr->getIndices());
958  ntsr->setWorldIndices(tsr->getWorldIndices());
959 
960  // weight relative frames less
961  if ((weight - 1.) < constants::eps)
962  if (spec.isRelative())
963  weight = 0.1;
964  }
965 
966  tsrs_.emplace_back(ntsr);
967  weights_.emplace_back(weight);
968 
969  dimension_ += ntsr->getDimension();
971 }
A shared pointer wrapper for robowflex::darts::TSR.
double tolerance_
Tolerance for solving.
Definition: tsr.h:991
std::vector< double > weights_
Weights on TSRs.
Definition: tsr.h:995
std::size_t dimension_
Total error dimension of set.
Definition: tsr.h:996
The specification of a TSR.
Definition: tsr.h:70
double tolerance
Tolerance on solution for solver.
Definition: tsr.h:110
bool isRelative() const
Returns true if TSR is a relative reference frame (not the world).
Definition: tsr.cpp:402
T emplace_back(T... args)
T min(T... args)
static const double eps
Definition: constants.h:16

◆ computeLimits()

void TSRSet::computeLimits ( )

Compute the upper and lower limits from the skeleton.

Definition at line 1242 of file tsr.cpp.

1243 {
1244  const auto &wi = getWorldIndices();
1245  std::size_t n = wi.size();
1246 
1247  upper_ = Eigen::VectorXd::Zero(n);
1248  lower_ = Eigen::VectorXd::Zero(n);
1249  for (std::size_t i = 0; i < n; ++i)
1250  {
1251  const auto &wii = wi[i];
1252  const auto &dof = world_->getSim()->getSkeleton(wii.first)->getDof(wii.second);
1253  // if (dof->isCyclic())
1254  // {
1255  // lower_[i] = -constants::pi;
1256  // upper_[i] = constants::pi;
1257  // }
1258  // else
1259  // {
1260  auto limits = dof->getPositionLimits();
1261  lower_[i] = limits.first;
1262  upper_[i] = limits.second;
1263  // }
1264  }
1265 }
Eigen::VectorXd upper_
Upper bounds on world configuration.
Definition: tsr.h:998
Eigen::VectorXd lower_
Lower bounds on world configuration.
Definition: tsr.h:999
const std::vector< std::pair< std::size_t, std::size_t > > & getWorldIndices() const
Get the world indices used.
Definition: tsr.cpp:1227

◆ distanceWorld()

double TSRSet::distanceWorld ( ) const

Get the current distance to satisfaction given the world state.

Returns
Distance to TSR set satisfaction.

Definition at line 1081 of file tsr.cpp.

1082 {
1083  Eigen::VectorXd x(getDimension());
1084  getErrorWorld(x);
1085  return x.norm();
1086 }
std::size_t getDimension() const
Get the error dimension of this set of TSRs.
Definition: tsr.cpp:1022
void getErrorWorld(Eigen::Ref< Eigen::VectorXd > error) const
Get the current error given the world state.
Definition: tsr.cpp:1027

◆ distanceWorldState()

double TSRSet::distanceWorldState ( const Eigen::Ref< const Eigen::VectorXd > &  world) const

Get the distance to satisfaction given a provided world configuration.

Parameters
[in]worldWorld configuration (from world indices).
Returns
Distance to TSR set satisfaction.

Definition at line 1088 of file tsr.cpp.

1089 {
1090  Eigen::VectorXd x(getDimension());
1091  getErrorWorldState(world, x);
1092  return x.norm();
1093 }
void getErrorWorldState(const Eigen::Ref< const Eigen::VectorXd > &world, Eigen::Ref< Eigen::VectorXd > error) const
Get the error given a provided world configuration.
Definition: tsr.cpp:1044

◆ enforceBoundsWorld()

void TSRSet::enforceBoundsWorld ( Eigen::Ref< Eigen::VectorXd >  world) const
private

Enforce upper and lower bounds on a world configuration.

Parameters
[in,out]worldWorld configuration to enforce.

Definition at line 1287 of file tsr.cpp.

1288 {
1289  if (upper_.size())
1290  world = world.cwiseMin(upper_);
1291  if (lower_.size())
1292  world = world.cwiseMax(lower_);
1293 }

◆ getDamping()

double TSRSet::getDamping ( ) const

Get the solver damping parameter.

Returns
The solver damping parameter.

Definition at line 1338 of file tsr.cpp.

1339 {
1340  return damping_;
1341 }
double damping_
Damping factor.
Definition: tsr.h:990

◆ getDimension()

std::size_t TSRSet::getDimension ( ) const

Get the error dimension of this set of TSRs.

Returns
The error dimension of the set of TSRs.

Definition at line 1022 of file tsr.cpp.

1023 {
1024  return dimension_;
1025 }

◆ getErrorWorld()

void TSRSet::getErrorWorld ( Eigen::Ref< Eigen::VectorXd >  error) const

Get the current error given the world state.

Parameters
[out]errorError value for all TSRs.

Definition at line 1027 of file tsr.cpp.

1028 {
1029  world_->lock();
1030 
1031  std::size_t i = 0;
1032  for (std::size_t j = 0; j < tsrs_.size(); ++j)
1033  {
1034  const auto &tsr = tsrs_[j];
1035  tsr->getErrorWorld(error.segment(i, tsr->getDimension()));
1036  error.segment(i, tsr->getDimension()) *= weights_[j];
1037 
1038  i += tsr->getDimension();
1039  }
1040 
1041  world_->unlock();
1042 }

◆ getErrorWorldState()

void TSRSet::getErrorWorldState ( const Eigen::Ref< const Eigen::VectorXd > &  world,
Eigen::Ref< Eigen::VectorXd >  error 
) const

Get the error given a provided world configuration.

Parameters
[in]worldWorld configuration (from world indices).
[out]errorError value for all TSRs.

Definition at line 1044 of file tsr.cpp.

1046 {
1047  world_->lock();
1048 
1049  std::size_t i = 0;
1050  for (std::size_t j = 0; j < tsrs_.size(); ++j)
1051  {
1052  const auto &tsr = tsrs_[j];
1053  tsr->getErrorWorldState(world, error.segment(i, tsr->getDimension()));
1054  error.segment(i, tsr->getDimension()) *= weights_[j];
1055 
1056  i += tsr->getDimension();
1057  }
1058 
1059  world_->unlock();
1060 }

◆ getJacobianWorldState()

void TSRSet::getJacobianWorldState ( const Eigen::Ref< const Eigen::VectorXd > &  world,
Eigen::Ref< Eigen::MatrixXd >  jacobian 
) const

Get the Jacobian given a provided world configuration.

Parameters
[in]worldWorld configuration (from world indices).
[out]jacobianJacobian value for all TSRs.

Definition at line 1062 of file tsr.cpp.

1064 {
1065  world_->lock();
1066 
1067  unsigned int i = 0;
1068  std::size_t n = world.size();
1069  for (std::size_t j = 0; j < tsrs_.size(); ++j)
1070  {
1071  const auto &tsr = tsrs_[j];
1072  tsr->getJacobianWorldState(world, jacobian.block(i, 0, tsr->getDimension(), n));
1073  jacobian.block(i, 0, tsr->getDimension(), n) *= weights_[j];
1074 
1075  i += tsr->getDimension();
1076  }
1077 
1078  world_->unlock();
1079 }

◆ getLimit()

double TSRSet::getLimit ( ) const

Get the solver limit parameter.

Returns
The solver limit parameter.

Definition at line 1328 of file tsr.cpp.

1329 {
1330  return limit_;
1331 }
double limit_
Step size limit.
Definition: tsr.h:989

◆ getMaxIterations()

std::size_t TSRSet::getMaxIterations ( ) const

Get the maximum iterations allowed.

Returns
The maximum solver iterations.

Definition at line 1204 of file tsr.cpp.

1205 {
1206  return maxIter_;
1207 }
std::size_t maxIter_
Maximum iterations to use for solving.
Definition: tsr.h:992

◆ getPositionsWorldState()

void TSRSet::getPositionsWorldState ( Eigen::Ref< Eigen::VectorXd >  world) const

Get the current world state.

Parameters
[out]worldState to fill.

Definition at line 1232 of file tsr.cpp.

1233 {
1234  const auto &wi = getWorldIndices();
1235  for (std::size_t i = 0; i < wi.size(); ++i)
1236  {
1237  const auto &wii = wi[i];
1238  world[i] = world_->getSim()->getSkeleton(wii.first)->getDof(wii.second)->getPosition();
1239  }
1240 }

◆ getStep()

double TSRSet::getStep ( ) const

Get the solver step parameter.

Returns
The solver step parameter.

Definition at line 1308 of file tsr.cpp.

1309 {
1310  return step_;
1311 }
double step_
Step scaling in gradient.
Definition: tsr.h:988

◆ getTolerance()

double TSRSet::getTolerance ( ) const

Get the numerical tolerance for solving.

Returns
The tolerance.

Definition at line 1209 of file tsr.cpp.

1210 {
1211  return tolerance_;
1212 }

◆ getTSRs()

const std::vector< TSRPtr > & TSRSet::getTSRs ( ) const

Get the TSRs that form the set.

Returns
The set of TSRs.

Definition at line 978 of file tsr.cpp.

979 {
980  return tsrs_;
981 }

◆ getWorldIndices()

const std::vector< std::pair< std::size_t, std::size_t > > & TSRSet::getWorldIndices ( ) const

Get the world indices used.

Returns
World indices.

Definition at line 1227 of file tsr.cpp.

1228 {
1229  return tsrs_[0]->getWorldIndices();
1230 }

◆ initialize()

void TSRSet::initialize ( )

Initialize this set of TSRs.

Definition at line 1214 of file tsr.cpp.

1215 {
1216  skel_indices_.clear();
1217  for (auto &tsr : tsrs_)
1218  {
1219  tsr->initialize();
1220  skel_indices_.emplace(tsr->getSkeletonIndex());
1221  }
1222 
1223  updateSolver();
1224  RBX_INFO("TSRSet: Initialized %d TSRs!", tsrs_.size());
1225 }
std::set< std::size_t > skel_indices_
All skeleton indices used by members of the set.
Definition: tsr.h:984
void updateSolver()
Update the solver information (iterations, tolerance, etc.)
Definition: tsr.cpp:1190
T clear(T... args)
T emplace(T... args)
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118

◆ numTSRs()

std::size_t TSRSet::numTSRs ( ) const

Get the number of TSRs in the set.

Returns
The number of TSRs.

Definition at line 973 of file tsr.cpp.

974 {
975  return tsrs_.size();
976 }

◆ print()

void TSRSet::print ( std::ostream out) const

Print out the TSRs in this set.

Parameters
[in]outOutput stream.

Definition at line 1295 of file tsr.cpp.

1296 {
1297  out << "TSRSet --------------------" << std::endl;
1298  for (const auto &tsr : tsrs_)
1299  tsr->getSpecification().print(out);
1300  out << "---------------------------" << std::endl;
1301 }
T endl(T... args)

◆ setDamping()

void TSRSet::setDamping ( double  damping)

Set the damping parameter in the solver.

Parameters
[in]dampingDamping parameter.

Definition at line 1333 of file tsr.cpp.

1334 {
1335  damping_ = damping;
1336 }

◆ setLimit()

void TSRSet::setLimit ( double  limit)

Set the limit parameter in the solver.

Parameters
[in]limitLimit parameter.

Definition at line 1323 of file tsr.cpp.

1324 {
1325  limit_ = limit;
1326 }

◆ setMaxIterations()

void TSRSet::setMaxIterations ( std::size_t  iterations)

Set the maximum iterations used for solving.

Parameters
[in]iterationsMax iterations to use.

Definition at line 1267 of file tsr.cpp.

1268 {
1269  maxIter_ = iterations;
1270 }

◆ setStep()

void TSRSet::setStep ( double  step)

Set the step parameter in the solver.

Parameters
[in]stepStep parameter.

Definition at line 1303 of file tsr.cpp.

1304 {
1305  step_ = step;
1306 }

◆ setTolerance()

void TSRSet::setTolerance ( double  tolerance)

Set the maximum tolerance used for solving.

Parameters
[in]toleranceNew tolerance.

Definition at line 1272 of file tsr.cpp.

1273 {
1274  tolerance_ = tolerance;
1275 }

◆ setWorld()

void TSRSet::setWorld ( const WorldPtr world)

Set the world used by this TSR set.

Parameters
[in]worldNew world to use.

Definition at line 983 of file tsr.cpp.

984 {
985  for (auto &tsr : tsrs_)
986  tsr->setWorld(world);
987 
988  world_ = world;
989  initialize();
990 }
void initialize()
Initialize this set of TSRs.
Definition: tsr.cpp:1214

◆ setWorldIndices()

void TSRSet::setWorldIndices ( const std::vector< std::pair< std::size_t, std::size_t >> &  indices)

Output world indices. TSR information for *WorldState methods uses this set of world indices. World indices are pairs of skeleton index and DoF index.

Parameters
[in]indicesIndices to use.

Definition at line 1016 of file tsr.cpp.

1017 {
1018  for (auto &tsr : tsrs_)
1019  tsr->setWorldIndices(indices);
1020 }

◆ setWorldLowerLimits()

void TSRSet::setWorldLowerLimits ( const Eigen::Ref< const Eigen::VectorXd > &  lower)

Set the lower limit on joints given their index in the world configuration.

Parameters
[in]lowerLower bounds on joints.

Definition at line 1282 of file tsr.cpp.

1283 {
1284  lower_ = lower;
1285 }

◆ setWorldUpperLimits()

void TSRSet::setWorldUpperLimits ( const Eigen::Ref< const Eigen::VectorXd > &  upper)

Set the upper limit on joints given their index in the world configuration.

Parameters
[in]upperUpper bounds on joints.

Definition at line 1277 of file tsr.cpp.

1278 {
1279  upper_ = upper;
1280 }

◆ solveGradientWorldState()

bool TSRSet::solveGradientWorldState ( Eigen::Ref< Eigen::VectorXd >  world)

Solve using gradient descent for a satisfying configuration given an initial world configuration.

Parameters
[in]worldWorld configuration (from world indices).
Returns
True on success, false on failure.

Definition at line 1135 of file tsr.cpp.

1136 {
1137  unsigned int iter = 0;
1138  double norm = 0;
1139  Eigen::VectorXd f(getDimension());
1140  Eigen::MatrixXd j(getDimension(), world.size());
1141 
1142  const double squared_tolerance = tolerance_ * tolerance_;
1143  const Eigen::VectorXd limit = Eigen::VectorXd::Constant(world.size(), limit_);
1144 
1145  world_->lock();
1146  getErrorWorldState(world, f);
1147 
1148  while ((norm = f.norm()) > squared_tolerance and iter++ < maxIter_)
1149  {
1150  getJacobianWorldState(world, j);
1151  if (qr_)
1152  world -= (step_ * j.colPivHouseholderQr().solve(f)).cwiseMin(limit).cwiseMax(-limit);
1153  else
1154  {
1155  if (damped_)
1156  {
1157  auto svd = j.jacobiSvd(Eigen::ComputeFullU | Eigen::ComputeFullV);
1158  auto lr = svd.rank();
1159  const auto &u = svd.matrixU().leftCols(lr);
1160  const auto &v = svd.matrixV().leftCols(lr);
1161  const auto &s = svd.singularValues().head(lr);
1162  const auto &d = Eigen::VectorXd::Constant(lr, damping_);
1163 
1164  const auto &damped = s.cwiseQuotient(s.cwiseProduct(s) + d.cwiseProduct(d));
1165 
1166  Eigen::MatrixXd tmp;
1167  tmp.noalias() = u.adjoint() * f;
1168  tmp = damped.asDiagonal().inverse() * tmp;
1169  auto step = v * tmp;
1170 
1171  world -= (step_ * step).cwiseMin(limit).cwiseMax(-limit);
1172  }
1173  else
1174  world -= (step_ * j.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(f))
1175  .cwiseMin(limit)
1176  .cwiseMax(-limit);
1177  }
1178 
1179  enforceBoundsWorld(world);
1180 
1181  getErrorWorldState(world, f);
1182  }
1183 
1184  world_->forceUpdate();
1185  world_->unlock();
1186 
1187  return norm < squared_tolerance;
1188 }
void getJacobianWorldState(const Eigen::Ref< const Eigen::VectorXd > &world, Eigen::Ref< Eigen::MatrixXd > jacobian) const
Get the Jacobian given a provided world configuration.
Definition: tsr.cpp:1062
bool damped_
If true, use damped SVD.
Definition: tsr.h:987
void enforceBoundsWorld(Eigen::Ref< Eigen::VectorXd > world) const
Enforce upper and lower bounds on a world configuration.
Definition: tsr.cpp:1287
bool qr_
If true, use QR in gradient solve. Else, SVD.
Definition: tsr.h:986

◆ solveWorld()

bool TSRSet::solveWorld ( )

Solve for a satisfying configuration given the current state of the world.

Returns
True on success, false on failure.

Definition at line 1095 of file tsr.cpp.

1096 {
1097  world_->lock();
1098 
1099  if (tsrs_.size() == 1)
1100  {
1101  bool r = tsrs_[0]->solveWorld();
1102  world_->unlock();
1103  return r;
1104  }
1105 
1106  auto sim = world_->getSim();
1107 
1108  bool r = true;
1109  for (const auto &skidx : skel_indices_)
1110  {
1111  auto skel = sim->getSkeleton(skidx);
1112  auto ik = skel->getIK(true);
1113  r &= ik->solveAndApply(true);
1114  }
1115 
1116  world_->unlock();
1117  return r;
1118 }

◆ solveWorldState()

bool TSRSet::solveWorldState ( Eigen::Ref< Eigen::VectorXd >  world)

Solve for a satisfying configuration given an initial world configuration.

Parameters
[in]worldWorld configuration (from world indices).
Returns
True on success, false on failure.

Definition at line 1120 of file tsr.cpp.

1121 {
1122  world_->lock();
1123  for (auto &tsr : tsrs_)
1124  tsr->setPositionsWorldState(world);
1125 
1126  bool r = solveWorld();
1127 
1128  for (auto &tsr : tsrs_)
1129  tsr->getPositionsWorldState(world);
1130 
1131  world_->unlock();
1132  return r;
1133 }
bool solveWorld()
Solve for a satisfying configuration given the current state of the world.
Definition: tsr.cpp:1095

◆ updateSolver()

void TSRSet::updateSolver ( )

Update the solver information (iterations, tolerance, etc.)

Definition at line 1190 of file tsr.cpp.

1191 {
1192  auto sim = world_->getSim();
1193  for (const auto &skidx : skel_indices_)
1194  {
1195  auto skel = sim->getSkeleton(skidx);
1196  auto ik = skel->getIK(true);
1197 
1198  auto sv = ik->getSolver();
1199  sv->setNumMaxIterations(maxIter_);
1200  sv->setTolerance(tolerance_);
1201  }
1202 }

◆ useDamping()

void TSRSet::useDamping ( bool  damping)

Set if damping is used in SVD solving.

Parameters
[in]dampingDamping value.

Definition at line 1343 of file tsr.cpp.

1344 {
1345  damped_ = damping;
1346 }

◆ useGroup()

void TSRSet::useGroup ( const std::string name)

Use the joints in a robot's group. Robot used is the target frame's structure.

Parameters
[in]nameName of group to use.

Definition at line 998 of file tsr.cpp.

999 {
1000  for (auto &tsr : tsrs_)
1001  tsr->useGroup(name);
1002 }

◆ useIndices()

void TSRSet::useIndices ( const std::vector< std::size_t > &  indices)

Use DoF indices for all TSRs computation.

Parameters
[in]indicesIndices to use.

Definition at line 1004 of file tsr.cpp.

1005 {
1006  for (auto &tsr : tsrs_)
1007  tsr->useIndices(indices);
1008 }

◆ useQR()

void TSRSet::useQR ( )

Use QR for solving.

Definition at line 1318 of file tsr.cpp.

1319 {
1320  qr_ = true;
1321 }

◆ useSVD()

void TSRSet::useSVD ( )

Use SVD for solving.

Definition at line 1313 of file tsr.cpp.

1314 {
1315  qr_ = false;
1316 }

◆ useWorldIndices()

void TSRSet::useWorldIndices ( const std::vector< std::pair< std::size_t, std::size_t >> &  indices)

Use World DoF indices for all TSRs computation. World indices are pairs of skeleton index and DoF index.

Parameters
[in]indicesIndices to use.

Definition at line 1010 of file tsr.cpp.

1011 {
1012  for (auto &tsr : tsrs_)
1013  tsr->useWorldIndices(indices);
1014 }

Member Data Documentation

◆ damped_

bool robowflex::darts::TSRSet::damped_ {true}
private

If true, use damped SVD.

Definition at line 987 of file tsr.h.

◆ damping_

double robowflex::darts::TSRSet::damping_ {1e-8}
private

Damping factor.

Definition at line 990 of file tsr.h.

◆ dimension_

std::size_t robowflex::darts::TSRSet::dimension_ {0}
private

Total error dimension of set.

Definition at line 996 of file tsr.h.

◆ limit_

double robowflex::darts::TSRSet::limit_ {1.}
private

Step size limit.

Definition at line 989 of file tsr.h.

◆ lower_

Eigen::VectorXd robowflex::darts::TSRSet::lower_
private

Lower bounds on world configuration.

Definition at line 999 of file tsr.h.

◆ maxIter_

std::size_t robowflex::darts::TSRSet::maxIter_ {50}
private

Maximum iterations to use for solving.

Definition at line 992 of file tsr.h.

◆ qr_

bool robowflex::darts::TSRSet::qr_ {false}
private

If true, use QR in gradient solve. Else, SVD.

Definition at line 986 of file tsr.h.

◆ skel_indices_

std::set<std::size_t> robowflex::darts::TSRSet::skel_indices_
private

All skeleton indices used by members of the set.

Definition at line 984 of file tsr.h.

◆ step_

double robowflex::darts::TSRSet::step_ {1.0}
private

Step scaling in gradient.

Definition at line 988 of file tsr.h.

◆ tolerance_

double robowflex::darts::TSRSet::tolerance_ {magic::DEFAULT_IK_TOLERANCE}
private

Tolerance for solving.

Definition at line 991 of file tsr.h.

◆ tsrs_

std::vector<TSRPtr> robowflex::darts::TSRSet::tsrs_
private

Set of TSRs.

Definition at line 994 of file tsr.h.

◆ upper_

Eigen::VectorXd robowflex::darts::TSRSet::upper_
private

Upper bounds on world configuration.

Definition at line 998 of file tsr.h.

◆ weights_

std::vector<double> robowflex::darts::TSRSet::weights_
private

Weights on TSRs.

Definition at line 995 of file tsr.h.

◆ world_

WorldPtr robowflex::darts::TSRSet::world_
private

World to use.

Definition at line 983 of file tsr.h.


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