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

The specification of a TSR. More...

#include <tsr.h>

Public Member Functions

Constructors
 Specification ()=default
 Default constructor. More...
 
 Specification (const std::string &structure, const std::string &target_frame, const Eigen::Ref< const Eigen::Vector3d > &position, const Eigen::Quaterniond &rotation)
 Constructor for basic pose TSR constrained in world frame. More...
 
void setTarget (const std::string &structure, const std::string &frame)
 Setting TSR Frame. More...
 
void setBase (const std::string &structure, const std::string &frame)
 Set the base frame. More...
 
void setFrame (const std::string &structure, const std::string &target, const std::string &base=magic::ROOT_FRAME)
 Set the base and target frame. More...
 
void addSuffix (const std::string &suffix)
 Add a suffix to the structures for the target and base frame. More...
 
void setPosition (const Eigen::Ref< const Eigen::Vector3d > &position)
 Setting TSR Pose. More...
 
void setPosition (double x, double y, double z)
 Set the position of the TSR. More...
 
void setRotation (const Eigen::Quaterniond &orientation)
 Set the rotation of the TSR. More...
 
void setRotation (double w, double x, double y, double z)
 Set the rotation of the TSR as a quaternion. More...
 
void setRotation (double x, double y, double z)
 Set the rotation of the TSR as XYZ Euler angles. More...
 
void setPose (const RobotPose &other)
 Set the pose of the TSR. More...
 
void setPose (const Eigen::Ref< const Eigen::Vector3d > &position, const Eigen::Quaterniond &rotation)
 Set the pose of the TSR. More...
 
void setPose (double xp, double yp, double zp, double wr, double xr, double yr, double zr)
 Set the pose of the TSR. More...
 
void setPoseFromWorld (const WorldPtr &world)
 Set the pose of the TSR for the desired frame in a provided world. Uses world's current configuration. More...
 
void setXPosTolerance (double bound)
 Setting Position Tolerances. More...
 
void setYPosTolerance (double bound)
 Set the Y position tolerance to (-bound, bound). More...
 
void setZPosTolerance (double bound)
 Set the Z position tolerance to (-bound, bound). More...
 
void setXPosTolerance (double lower, double upper)
 Set the X position tolerance to (lower, upper). More...
 
void setYPosTolerance (double lower, double upper)
 Set the Y position tolerance to (lower, upper). More...
 
void setZPosTolerance (double lower, double upper)
 Set the Z position tolerance to (lower, upper). More...
 
void setNoXPosTolerance ()
 Set no position tolerance on the X-axis. More...
 
void setNoYPosTolerance ()
 Set no position tolerance on the Y-axis. More...
 
void setNoZPosTolerance ()
 Set no position tolerance on the Z-axis. More...
 
void setNoPosTolerance ()
 Set no position tolerance at all. More...
 
void setXRotTolerance (double bound)
 Setting Orientation Tolerances. More...
 
void setYRotTolerance (double bound)
 Set the Y orientation tolerance to (-bound, bound). More...
 
void setZRotTolerance (double bound)
 Set the Z orientation tolerance to (-bound, bound). More...
 
void setXRotTolerance (double lower, double upper)
 Set the X orientation tolerance to (lower, upper). More...
 
void setYRotTolerance (double lower, double upper)
 Set the Y orientation tolerance to (lower, upper). More...
 
void setZRotTolerance (double lower, double upper)
 Set the Z orientation tolerance to (lower, upper). More...
 
void setNoXRotTolerance ()
 Set no orientation tolerance on the X-axis. More...
 
void setNoYRotTolerance ()
 Set no orientation tolerance on the Y-axis. More...
 
void setNoZRotTolerance ()
 Set no orientation tolerance on the Z-axis. More...
 
void setNoRotTolerance ()
 Set no orientation tolerance at all. More...
 
Eigen::Vector3d getPosition () const
 Getters and Informative Methods. More...
 
Eigen::Quaterniond getRotation () const
 Get the current desired orientation. More...
 
Eigen::Vector3d getEulerRotation () const
 Get the current desired orientation. More...
 
bool isPositionConstrained () const
 Returns true if TSR is position constrained. More...
 
bool isRotationConstrained () const
 Returns true if TSR is orientation constrained. More...
 
bool isRelative () const
 Returns true if TSR is a relative reference frame (not the world). More...
 
void print (std::ostream &out) const
 Print out this TSR information. More...
 
bool intersect (const Specification &other)
 Operations. More...
 

Public Attributes

struct {
   std::string   structure
 Structure target frame is in. More...
 
   std::string   frame
 Name of target frame. More...
 
target
 Target frame. More...
 
struct {
   std::string   structure
 Structure base frame is in. More...
 
   std::string   frame {magic::ROOT_FRAME}
 Name of base frame. More...
 
base
 Base frame. More...
 
RobotPose pose {RobotPose::Identity()}
 Pose of TSR. More...
 
struct {
   ROBOWFLEX_EIGEN Eigen::Vector3d   upper {magic::DEFAULT_IK_TOLERANCES}
 Upper position tolerance. More...
 
   Eigen::Vector3d   lower {-magic::DEFAULT_IK_TOLERANCES}
 Lower position tolerance. More...
 
position
 Position tolerances. More...
 
struct {
   ROBOWFLEX_EIGEN Eigen::Vector3d   upper {magic::DEFAULT_IK_TOLERANCES}
 Upper orientation tolerance. More...
 
   Eigen::Vector3d   lower {-magic::DEFAULT_IK_TOLERANCES}
 Lower orientation tolerance. More...
 
orientation
 Orientation tolerances. More...
 
std::size_t dimension {6}
 Number of constrained dimensions. More...
 
std::vector< bool > indices {std::vector<bool>(6, true)}
 Vector of active constraints. If an index is true, that constraint is active. Ordered by X-, Y-, Z- orientation constraints, then X-, Y-, Z- position. More...
 
std::size_t maxIter {50}
 Maximum iterations for solver. More...
 
double tolerance {magic::DEFAULT_IK_TOLERANCE}
 Tolerance on solution for solver. More...
 

Private Member Functions

void fixBounds ()
 Fixes bounds so they are correct. More...
 
std::size_t getDimension () const
 Compute and return constraint dimension of the TSR. More...
 
bool isPosConstrained (double lower, double upper) const
 Checks if two values correspond to a position constraint. More...
 
bool isRotConstrained (double lower, double upper) const
 Checks if two values correspond to a orientation constraint. More...
 

Detailed Description

The specification of a TSR.

Definition at line 69 of file tsr.h.

Constructor & Destructor Documentation

◆ Specification() [1/2]

robowflex::darts::TSR::Specification::Specification ( )
default

Default constructor.

◆ Specification() [2/2]

TSR::Specification::Specification ( const std::string structure,
const std::string target_frame,
const Eigen::Ref< const Eigen::Vector3d > &  position,
const Eigen::Quaterniond &  rotation 
)

Constructor for basic pose TSR constrained in world frame.

Parameters
[in]structureStructure TSR is on (both target and base frames).
[in]target_frameTarget frame.
[in]positionDesired position.
[in]rotationDesired orientation.

TSR::Specification

Definition at line 25 of file tsr.cpp.

28 {
29  setTarget(structure, target_frame);
30  setPose(position, rotation);
31 }
std::string structure
Structure target frame is in.
Definition: tsr.h:76
void setTarget(const std::string &structure, const std::string &frame)
Setting TSR Frame.
Definition: tsr.cpp:33
void setPose(const RobotPose &other)
Set the pose of the TSR.
Definition: tsr.cpp:93
struct robowflex::darts::TSR::Specification::@5 position
Position tolerances.

Member Function Documentation

◆ addSuffix()

void TSR::Specification::addSuffix ( const std::string suffix)

Add a suffix to the structures for the target and base frame.

Parameters
[in]suffixSuffix to add to structures in target and base frame.

Definition at line 58 of file tsr.cpp.

59 {
60  target.structure = target.structure + suffix;
61  base.structure = base.structure + suffix;
62 }
ROBOWFLEX_EIGEN struct robowflex::darts::TSR::Specification::@3 target
Target frame.
struct robowflex::darts::TSR::Specification::@4 base
Base frame.

◆ fixBounds()

void TSR::Specification::fixBounds ( )
private

Fixes bounds so they are correct.

Definition at line 262 of file tsr.cpp.

263 {
264  {
265  Eigen::Vector3d u, l;
266  for (std::size_t i = 0; i < 3; ++i)
267  {
268  u[i] = std::max(position.lower[i], position.upper[i]);
269  l[i] = std::min(position.lower[i], position.upper[i]);
270  }
271 
272  position.lower = l;
273  position.upper = u;
274  }
275 
276  {
277  Eigen::Vector3d u, l;
278  for (std::size_t i = 0; i < 3; ++i)
279  {
280  u[i] = std::max({orientation.lower[i], orientation.upper[i], -constants::pi});
281  l[i] = std::min({orientation.lower[i], orientation.upper[i], constants::pi});
282  }
283 
284  orientation.lower = l;
285  orientation.upper = u;
286  }
287 }
struct robowflex::darts::TSR::Specification::@6 orientation
Orientation tolerances.
T max(T... args)
T min(T... args)
static const double pi
Definition: constants.h:21

◆ getDimension()

std::size_t TSR::Specification::getDimension ( ) const
private

Compute and return constraint dimension of the TSR.

Returns
Dimension of TSR.

Definition at line 289 of file tsr.cpp.

290 {
291  std::size_t k = 0;
292  for (const auto &idx : indices)
293  {
294  if (idx)
295  k++;
296  }
297 
298  return k;
299 }
std::vector< bool > indices
Vector of active constraints. If an index is true, that constraint is active. Ordered by X-,...
Definition: tsr.h:107

◆ getEulerRotation()

Eigen::Vector3d TSR::Specification::getEulerRotation ( ) const

Get the current desired orientation.

Returns
Orientation as XYZ Euler angles.

Definition at line 321 of file tsr.cpp.

322 {
323  return getRotation().toRotationMatrix().eulerAngles(0, 1, 2);
324 }
Eigen::Quaterniond getRotation() const
Get the current desired orientation.
Definition: tsr.cpp:316

◆ getPosition()

Eigen::Vector3d TSR::Specification::getPosition ( ) const

Getters and Informative Methods.

Get the current desired position.

Returns
Position vector.

Definition at line 311 of file tsr.cpp.

312 {
313  return pose.translation();
314 }
RobotPose pose
Pose of TSR.
Definition: tsr.h:86

◆ getRotation()

Eigen::Quaterniond TSR::Specification::getRotation ( ) const

Get the current desired orientation.

Returns
Orientation quaternion.

Definition at line 316 of file tsr.cpp.

317 {
318  return TF::getPoseRotation(pose);
319 }
Eigen::Quaterniond getPoseRotation(const RobotPose &pose)
Get the rotational component of a robot pose.
Definition: tf.cpp:69

◆ intersect()

bool TSR::Specification::intersect ( const Specification other)

Operations.

Compute the intersection of this TSR with the other.

Returns
True if successful, false on failure.

Definition at line 326 of file tsr.cpp.

327 {
328  // must be same reference frame
329  if (target.structure != other.target.structure or target.frame != other.target.frame)
330  return false;
331 
332  if (base.structure != other.base.structure or base.frame != other.base.frame)
333  return false;
334 
335  // TODO: Check if rotations overlap
336  // if (getRotation().angularDistance(other.getRotation()) > magic::DEFAULT_IK_TOLERANCE)
337  // return false;
338 
339  Eigen::Vector3d p = getPosition();
340  Eigen::Vector3d op = other.getPosition();
341 
342  // check if positions overlap
343  for (std::size_t i = 0; i < 3; ++i)
344  {
345  double pi = p[i], piu = position.upper[i], pil = position.lower[i];
346  double opi = op[i], opiu = other.position.upper[i], opil = other.position.lower[i];
347 
348  // pi---------> piu
349  // --|------|------|------|-- axis
350  // opil <---------opi
351  // Check if overlap
352 
353  if (pi < opi)
354  if ((pi + piu) < (opi + opil))
355  return false;
356 
357  // opi--------> opiu
358  // --|------|------|------|-- axis
359  // pil <----------pi
360  // Check if overlap
361 
362  if (pi > opi)
363  if ((pi + pil) > (opi + opiu))
364  return false;
365  }
366 
367  Eigen::Vector3d np;
368 
369  if (not isRotationConstrained())
370  setRotation(other.getRotation());
371 
372  // enforce new bounds
373  for (std::size_t i = 0; i < 3; ++i)
374  {
375  if (other.orientation.lower[i] > orientation.lower[i])
376  orientation.lower[i] = other.orientation.lower[i];
377  if (other.orientation.upper[i] < orientation.upper[i])
378  orientation.upper[i] = other.orientation.upper[i];
379 
380  double pi = p[i], piu = position.upper[i], pil = position.lower[i];
381  double opi = op[i], opiu = other.position.upper[i], opil = other.position.lower[i];
382 
383  double low = std::max(pi + pil, opi + opil);
384  double high = std::min(pi + piu, opi + opiu);
385 
386  np[i] = (high + low) / 2.;
387  double v = std::fabs(high - np[i]);
388 
389  position.upper[i] = v;
390  position.lower[i] = -v;
391 
392  indices[i] = isRotConstrained(orientation.lower[i], orientation.upper[i]);
393  indices[3 + i] = isPosConstrained(-v, v);
394  }
395 
397  setPosition(np);
398 
399  return true;
400 }
bool isPosConstrained(double lower, double upper) const
Checks if two values correspond to a position constraint.
Definition: tsr.cpp:301
bool isRotConstrained(double lower, double upper) const
Checks if two values correspond to a orientation constraint.
Definition: tsr.cpp:306
void setRotation(const Eigen::Quaterniond &orientation)
Set the rotation of the TSR.
Definition: tsr.cpp:74
bool isRotationConstrained() const
Returns true if TSR is orientation constrained.
Definition: tsr.cpp:416
std::size_t getDimension() const
Compute and return constraint dimension of the TSR.
Definition: tsr.cpp:289
std::size_t dimension
Number of constrained dimensions.
Definition: tsr.h:102
Eigen::Vector3d getPosition() const
Getters and Informative Methods.
Definition: tsr.cpp:311
void setPosition(const Eigen::Ref< const Eigen::Vector3d > &position)
Setting TSR Pose.
Definition: tsr.cpp:64
T fabs(T... args)

◆ isPosConstrained()

bool TSR::Specification::isPosConstrained ( double  lower,
double  upper 
) const
private

Checks if two values correspond to a position constraint.

Returns
If (lower, upper) is bounded or not.

Definition at line 301 of file tsr.cpp.

302 {
304 }
Eigen::Vector3d lower
Lower position tolerance.
Definition: tsr.h:92
ROBOWFLEX_EIGEN Eigen::Vector3d upper
Upper position tolerance.
Definition: tsr.h:91
T isfinite(T... args)

◆ isPositionConstrained()

bool TSR::Specification::isPositionConstrained ( ) const

Returns true if TSR is position constrained.

Returns
True if position constrained.

Definition at line 407 of file tsr.cpp.

408 {
409  bool value = false;
410  for (std::size_t i = 0; i < 3; ++i)
411  value |= isPosConstrained(position.lower[i], position.upper[i]);
412 
413  return value;
414 }

◆ isRelative()

bool TSR::Specification::isRelative ( ) const

Returns true if TSR is a relative reference frame (not the world).

Returns
True if this is a relative reference frame.

Definition at line 402 of file tsr.cpp.

403 {
404  return base.frame != magic::ROOT_FRAME;
405 }
static const std::string ROOT_FRAME
Definition: tsr.h:31

◆ isRotationConstrained()

bool TSR::Specification::isRotationConstrained ( ) const

Returns true if TSR is orientation constrained.

Returns
True if orientation constrained.

Definition at line 416 of file tsr.cpp.

417 {
418  bool value = false;
419  for (std::size_t i = 0; i < 3; ++i)
420  value |= isRotConstrained(orientation.lower[i], orientation.upper[i]);
421 
422  return value;
423 }

◆ isRotConstrained()

bool TSR::Specification::isRotConstrained ( double  lower,
double  upper 
) const
private

Checks if two values correspond to a orientation constraint.

Returns
If (lower, upper) is bounded or not.

Definition at line 306 of file tsr.cpp.

307 {
308  return std::abs(upper - lower) < constants::two_pi;
309 }
static const double two_pi
Definition: constants.h:24

◆ print()

void TSR::Specification::print ( std::ostream out) const

Print out this TSR information.

Parameters
[in]outOutput stream.

Definition at line 425 of file tsr.cpp.

426 {
427  if (isRelative())
428  out << boost::format("B:%1%:%2% => T:%3%:%4%") //
429  % base.frame % base.structure % target.frame % target.structure;
430  else
431  out << boost::format("T:%1%:%2%") //
432  % target.frame % target.structure;
433 
434  out << std::endl;
435  out << "Position Orientation" << std::endl;
436 
437  auto p = getPosition();
438  auto o = getRotation();
439  out << boost::format( //
440  " x:%1$+07.4f (%2$+07.4f, %3$+07.4f) [%7%] x:%4$+07.4f (%5$+07.4f, %6$+07.4f) [%8%]") //
441  % p[0] % position.lower[0] % position.upper[0] //
442  % o.x() % orientation.lower[0] % orientation.upper[0] //
443  % indices[3] % indices[0];
444  out << std::endl;
445  out << boost::format( //
446  " y:%1$+07.4f (%2$+07.4f, %3$+07.4f) [%7%] y:%4$+07.4f (%5$+07.4f, %6$+07.4f) [%8%]") //
447  % p[1] % position.lower[1] % position.upper[1] //
448  % o.y() % orientation.lower[1] % orientation.upper[1] //
449  % indices[4] % indices[1];
450  out << std::endl;
451  out << boost::format( //
452  " z:%1$+07.4f (%2$+07.4f, %3$+07.4f) [%7%] z:%4$+07.4f (%5$+07.4f, %6$+07.4f) [%8%]") //
453  % p[2] % position.lower[2] % position.upper[2] //
454  % o.z() % orientation.lower[2] % orientation.upper[2] //
455  % indices[5] % indices[2];
456  out << std::endl;
457  out << boost::format(" w:%1$+07.4f") % o.w();
458  out << std::endl;
459 }
bool isRelative() const
Returns true if TSR is a relative reference frame (not the world).
Definition: tsr.cpp:402
T endl(T... args)
std::string format(const std::string &fmt, Args &&... args)
Recursion base case, return string form of formatted arguments.
Definition: log.h:60

◆ setBase()

void TSR::Specification::setBase ( const std::string structure,
const std::string frame 
)

Set the base frame.

Parameters
[in]structureStructure frame is in.
[in]frameFrame name.

Definition at line 42 of file tsr.cpp.

43 {
44  base.structure = structure;
45  base.frame = frame;
46 }
std::string frame
Name of target frame.
Definition: tsr.h:77

◆ setFrame()

void TSR::Specification::setFrame ( const std::string structure,
const std::string target,
const std::string base = magic::ROOT_FRAME 
)

Set the base and target frame.

Parameters
[in]structureStructure frames are in.
[in]targetTarget frame name.
[in]baseBase frame name.

Definition at line 48 of file tsr.cpp.

50 {
51  target.structure = structure;
52  base.structure = structure;
53 
54  target.frame = target_frame;
55  base.frame = base_frame;
56 }

◆ setNoPosTolerance()

void TSR::Specification::setNoPosTolerance ( )

Set no position tolerance at all.

Definition at line 233 of file tsr.cpp.

234 {
238 }
void setNoZPosTolerance()
Set no position tolerance on the Z-axis.
Definition: tsr.cpp:228
void setNoXPosTolerance()
Set no position tolerance on the X-axis.
Definition: tsr.cpp:218
void setNoYPosTolerance()
Set no position tolerance on the Y-axis.
Definition: tsr.cpp:223

◆ setNoRotTolerance()

void TSR::Specification::setNoRotTolerance ( )

Set no orientation tolerance at all.

Definition at line 255 of file tsr.cpp.

256 {
260 }
void setNoXRotTolerance()
Set no orientation tolerance on the X-axis.
Definition: tsr.cpp:240
void setNoZRotTolerance()
Set no orientation tolerance on the Z-axis.
Definition: tsr.cpp:250
void setNoYRotTolerance()
Set no orientation tolerance on the Y-axis.
Definition: tsr.cpp:245

◆ setNoXPosTolerance()

void TSR::Specification::setNoXPosTolerance ( )

Set no position tolerance on the X-axis.

Definition at line 218 of file tsr.cpp.

219 {
221 }
void setXPosTolerance(double bound)
Setting Position Tolerances.
Definition: tsr.cpp:128

◆ setNoXRotTolerance()

void TSR::Specification::setNoXRotTolerance ( )

Set no orientation tolerance on the X-axis.

Definition at line 240 of file tsr.cpp.

241 {
243 }
void setXRotTolerance(double bound)
Setting Orientation Tolerances.
Definition: tsr.cpp:173

◆ setNoYPosTolerance()

void TSR::Specification::setNoYPosTolerance ( )

Set no position tolerance on the Y-axis.

Definition at line 223 of file tsr.cpp.

224 {
226 }
void setYPosTolerance(double bound)
Set the Y position tolerance to (-bound, bound).
Definition: tsr.cpp:133

◆ setNoYRotTolerance()

void TSR::Specification::setNoYRotTolerance ( )

Set no orientation tolerance on the Y-axis.

Definition at line 245 of file tsr.cpp.

246 {
248 }
void setYRotTolerance(double bound)
Set the Y orientation tolerance to (-bound, bound).
Definition: tsr.cpp:178

◆ setNoZPosTolerance()

void TSR::Specification::setNoZPosTolerance ( )

Set no position tolerance on the Z-axis.

Definition at line 228 of file tsr.cpp.

229 {
231 }
void setZPosTolerance(double bound)
Set the Z position tolerance to (-bound, bound).
Definition: tsr.cpp:138

◆ setNoZRotTolerance()

void TSR::Specification::setNoZRotTolerance ( )

Set no orientation tolerance on the Z-axis.

Definition at line 250 of file tsr.cpp.

251 {
253 }
void setZRotTolerance(double bound)
Set the Z orientation tolerance to (-bound, bound).
Definition: tsr.cpp:183

◆ setPose() [1/3]

void TSR::Specification::setPose ( const Eigen::Ref< const Eigen::Vector3d > &  position,
const Eigen::Quaterniond &  rotation 
)

Set the pose of the TSR.

Parameters
[in]positionDesired position.
[in]rotationDesired rotation.

Definition at line 98 of file tsr.cpp.

100 {
101  pose = TF::createPoseQ(position, rotation);
102 }
RobotPose createPoseQ(double x, double y, double z, double W, double X, double Y, double Z)
Creates a robot pose from a linear component and a Quaternion.
Definition: tf.cpp:47

◆ setPose() [2/3]

void TSR::Specification::setPose ( const RobotPose other)

Set the pose of the TSR.

Parameters
[in]otherPose to use.

Definition at line 93 of file tsr.cpp.

94 {
95  pose = other;
96 }

◆ setPose() [3/3]

void TSR::Specification::setPose ( double  xp,
double  yp,
double  zp,
double  wr,
double  xr,
double  yr,
double  zr 
)

Set the pose of the TSR.

Parameters
[in]xpX-coordinate of position.
[in]ypY-coordinate of position.
[in]zpZ-coordinate of position.
[in]wrW-component of quaternion.
[in]xrX-component of quaternion.
[in]yrY-component of quaternion.
[in]zrZ-component of quaternion.

Definition at line 104 of file tsr.cpp.

105 {
106  setPosition(xp, yp, zp);
107  setRotation(wr, xr, yr, zr);
108 }

◆ setPoseFromWorld()

void TSR::Specification::setPoseFromWorld ( const WorldPtr world)

Set the pose of the TSR for the desired frame in a provided world. Uses world's current configuration.

Parameters
[in]worldWorld to copy transform from.

Definition at line 110 of file tsr.cpp.

111 {
112  const auto &sim = world->getSim();
113 
114  const auto &tskl = sim->getSkeleton(target.structure);
115  const auto &tbn = tskl->getBodyNode(target.frame);
116 
117  if (base.frame != magic::ROOT_FRAME)
118  {
119  const auto &bskl = sim->getSkeleton(base.structure);
120  const auto &bbn = bskl->getBodyNode(base.frame);
121 
122  pose = tbn->getTransform(bbn);
123  }
124  else
125  pose = tbn->getTransform();
126 }

◆ setPosition() [1/2]

void TSR::Specification::setPosition ( const Eigen::Ref< const Eigen::Vector3d > &  position)

Setting TSR Pose.

Set the position of the TSR.

Parameters
[in]positionPosition vector.

Definition at line 64 of file tsr.cpp.

65 {
66  pose.translation() = position;
67 }

◆ setPosition() [2/2]

void TSR::Specification::setPosition ( double  x,
double  y,
double  z 
)

Set the position of the TSR.

Parameters
[in]xX-coordinate.
[in]yY-coordinate.
[in]zZ-coordinate.

Definition at line 69 of file tsr.cpp.

70 {
71  setPosition(Eigen::Vector3d(x, y, z));
72 }

◆ setRotation() [1/3]

void TSR::Specification::setRotation ( const Eigen::Quaterniond &  orientation)

Set the rotation of the TSR.

Parameters
[in]orientationDesired quaternion.

Definition at line 74 of file tsr.cpp.

75 {
76  pose.linear() = orientation.toRotationMatrix();
77 }

◆ setRotation() [2/3]

void TSR::Specification::setRotation ( double  w,
double  x,
double  y,
double  z 
)

Set the rotation of the TSR as a quaternion.

Parameters
[in]wW-component of quaternion.
[in]xX-component of quaternion.
[in]yY-component of quaternion.
[in]zZ-component of quaternion.

Definition at line 79 of file tsr.cpp.

80 {
81  setRotation(Eigen::Quaterniond(w, x, y, z));
82 }

◆ setRotation() [3/3]

void TSR::Specification::setRotation ( double  x,
double  y,
double  z 
)

Set the rotation of the TSR as XYZ Euler angles.

Parameters
[in]xX-component of rotation.
[in]yY-component of rotation.
[in]zZ-component of rotation.

Definition at line 84 of file tsr.cpp.

85 {
86  auto n = Eigen::AngleAxisd(x, Eigen::Vector3d::UnitX()) * //
87  Eigen::AngleAxisd(y, Eigen::Vector3d::UnitY()) * //
88  Eigen::AngleAxisd(z, Eigen::Vector3d::UnitZ());
89 
90  setRotation(n);
91 }

◆ setTarget()

void TSR::Specification::setTarget ( const std::string structure,
const std::string frame 
)

Setting TSR Frame.

Set the target frame. Sets base frame structure as well if not already set.

Parameters
[in]structureStructure frame is in.
[in]frameFrame name.

Definition at line 33 of file tsr.cpp.

34 {
35  target.structure = structure;
36  target.frame = frame;
37 
38  if (base.structure.empty())
39  base.structure = structure;
40 }

◆ setXPosTolerance() [1/2]

void TSR::Specification::setXPosTolerance ( double  bound)

Setting Position Tolerances.

Set the X position tolerance to (-bound, bound).

Parameters
[in]boundBound to set.

Definition at line 128 of file tsr.cpp.

129 {
130  setXPosTolerance(-bound, bound);
131 }

◆ setXPosTolerance() [2/2]

void TSR::Specification::setXPosTolerance ( double  lower,
double  upper 
)

Set the X position tolerance to (lower, upper).

Parameters
[in]lowerLower bound.
[in]upperUpper bound.

Definition at line 143 of file tsr.cpp.

144 {
145  position.lower[0] = lower;
146  position.upper[0] = upper;
147  fixBounds();
148 
151 }
void fixBounds()
Fixes bounds so they are correct.
Definition: tsr.cpp:262

◆ setXRotTolerance() [1/2]

void TSR::Specification::setXRotTolerance ( double  bound)

Setting Orientation Tolerances.

Set the X orientation tolerance to (-bound, bound).

Parameters
[in]boundBound to set.

Definition at line 173 of file tsr.cpp.

174 {
175  setXRotTolerance(-bound, bound);
176 }

◆ setXRotTolerance() [2/2]

void TSR::Specification::setXRotTolerance ( double  lower,
double  upper 
)

Set the X orientation tolerance to (lower, upper).

Parameters
[in]lowerLower bound.
[in]upperUpper bound.

Definition at line 188 of file tsr.cpp.

189 {
190  orientation.lower[0] = lower;
191  orientation.upper[0] = upper;
192  fixBounds();
193 
196 }

◆ setYPosTolerance() [1/2]

void TSR::Specification::setYPosTolerance ( double  bound)

Set the Y position tolerance to (-bound, bound).

Parameters
[in]boundBound to set.

Definition at line 133 of file tsr.cpp.

134 {
135  setYPosTolerance(-bound, bound);
136 }

◆ setYPosTolerance() [2/2]

void TSR::Specification::setYPosTolerance ( double  lower,
double  upper 
)

Set the Y position tolerance to (lower, upper).

Parameters
[in]lowerLower bound.
[in]upperUpper bound.

Definition at line 153 of file tsr.cpp.

154 {
155  position.lower[1] = lower;
156  position.upper[1] = upper;
157  fixBounds();
158 
161 }

◆ setYRotTolerance() [1/2]

void TSR::Specification::setYRotTolerance ( double  bound)

Set the Y orientation tolerance to (-bound, bound).

Parameters
[in]boundBound to set.

Definition at line 178 of file tsr.cpp.

179 {
180  setYRotTolerance(-bound, bound);
181 }

◆ setYRotTolerance() [2/2]

void TSR::Specification::setYRotTolerance ( double  lower,
double  upper 
)

Set the Y orientation tolerance to (lower, upper).

Parameters
[in]lowerLower bound.
[in]upperUpper bound.

Definition at line 198 of file tsr.cpp.

199 {
200  orientation.lower[1] = lower;
201  orientation.upper[1] = upper;
202  fixBounds();
203 
206 }

◆ setZPosTolerance() [1/2]

void TSR::Specification::setZPosTolerance ( double  bound)

Set the Z position tolerance to (-bound, bound).

Parameters
[in]boundBound to set.

Definition at line 138 of file tsr.cpp.

139 {
140  setZPosTolerance(-bound, bound);
141 }

◆ setZPosTolerance() [2/2]

void TSR::Specification::setZPosTolerance ( double  lower,
double  upper 
)

Set the Z position tolerance to (lower, upper).

Parameters
[in]lowerLower bound.
[in]upperUpper bound.

Definition at line 163 of file tsr.cpp.

164 {
165  position.lower[2] = lower;
166  position.upper[2] = upper;
167  fixBounds();
168 
171 }

◆ setZRotTolerance() [1/2]

void TSR::Specification::setZRotTolerance ( double  bound)

Set the Z orientation tolerance to (-bound, bound).

Parameters
[in]boundBound to set.

Definition at line 183 of file tsr.cpp.

184 {
185  setZRotTolerance(-bound, bound);
186 }

◆ setZRotTolerance() [2/2]

void TSR::Specification::setZRotTolerance ( double  lower,
double  upper 
)

Set the Z orientation tolerance to (lower, upper).

Parameters
[in]lowerLower bound.
[in]upperUpper bound.

Definition at line 208 of file tsr.cpp.

209 {
210  orientation.lower[2] = lower;
211  orientation.upper[2] = upper;
212  fixBounds();
213 
216 }

Member Data Documentation

◆ 

struct { ... } robowflex::darts::TSR::Specification::base

Base frame.

◆ dimension

std::size_t robowflex::darts::TSR::Specification::dimension {6}

Number of constrained dimensions.

Definition at line 102 of file tsr.h.

◆ frame

std::string robowflex::darts::TSR::Specification::frame {magic::ROOT_FRAME}

Name of target frame.

Name of base frame.

Definition at line 77 of file tsr.h.

◆ indices

std::vector<bool> robowflex::darts::TSR::Specification::indices {std::vector<bool>(6, true)}

Vector of active constraints. If an index is true, that constraint is active. Ordered by X-, Y-, Z- orientation constraints, then X-, Y-, Z- position.

Definition at line 107 of file tsr.h.

◆ lower

Eigen::Vector3d robowflex::darts::TSR::Specification::lower {-magic::DEFAULT_IK_TOLERANCES}

Lower position tolerance.

Lower orientation tolerance.

Definition at line 92 of file tsr.h.

◆ maxIter

std::size_t robowflex::darts::TSR::Specification::maxIter {50}

Maximum iterations for solver.

Definition at line 109 of file tsr.h.

◆ 

struct { ... } robowflex::darts::TSR::Specification::orientation

Orientation tolerances.

◆ pose

RobotPose robowflex::darts::TSR::Specification::pose {RobotPose::Identity()}

Pose of TSR.

Definition at line 86 of file tsr.h.

◆ 

struct { ... } robowflex::darts::TSR::Specification::position

Position tolerances.

◆ structure

std::string robowflex::darts::TSR::Specification::structure

Structure target frame is in.

Structure base frame is in.

Definition at line 76 of file tsr.h.

◆ 

ROBOWFLEX_EIGEN { ... } robowflex::darts::TSR::Specification::target

Target frame.

◆ tolerance

double robowflex::darts::TSR::Specification::tolerance {magic::DEFAULT_IK_TOLERANCE}

Tolerance on solution for solver.

Definition at line 110 of file tsr.h.

◆ upper

ROBOWFLEX_EIGEN Eigen::Vector3d robowflex::darts::TSR::Specification::upper {magic::DEFAULT_IK_TOLERANCES}

Upper position tolerance.

Upper orientation tolerance.

Definition at line 91 of file tsr.h.


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