Robowflex  v0.1
Making MoveIt Easy
robowflex::darts Namespace Reference

DART-based robot modeling and planning. More...

Namespaces

 IO
 
 magic
 

Classes

class  ACM
 Allowable collision matrix for robowflex::darts::Structure. More...
 
class  Viewer
 Viewer class. More...
 
class  Window
 Open Scene Graph GUI for DART visualization. More...
 
class  Widget
 Abstract class for IMGUI Widget. More...
 
class  ImGuiElement
 Abstract GUI element. More...
 
class  TextElement
 A basic text element. More...
 
class  CheckboxElement
 A checkbox element that modifies a boolean. More...
 
class  ButtonElement
 A basic push-button element. More...
 
class  RenderElement
 Generic rendered element. Use callback to display whatever GUI elements needed. More...
 
class  LinePlotElement
 Line plot element. Displays an updated line graph of data. More...
 
class  WindowWidget
 IMGUI widget to add interactive GUI elements programmatically. More...
 
class  TSREditWidget
 IMGUI widget to design TSRs. More...
 
class  TSRSolveWidget
 Class for solving a set of TSRs. More...
 
class  Joint
 Abstract controllable joint for robowflex::darts::StateSpace. More...
 
class  RnJoint
 A real vector joint of n dimensions. More...
 
class  SO2Joint
 A SO(2) joint. Bounds are from -pi to pi, and wraps. More...
 
class  SO3Joint
 A SO(3) joint modeled with quaternions. More...
 
class  DARTPlanner
 Wrapper for easy access to DART planning tools via standard Robowflex interface. More...
 
class  ConstraintExtractor
 Helper class to manage extracting states from a possibly constrained state space. More...
 
class  TSRGoal
 A sampleable goal region for OMPL for a set of TSRs. Samples goals in a separate thread using a clone of the world. More...
 
class  JointRegionGoal
 A joint space goal volume. More...
 
class  PlanBuilder
 A helper class to setup common OMPL structures for planning. More...
 
class  Robot
 A sampleable goal region for OMPL for a set of TSRs. Samples goals in a separate thread using a clone of the world. More...
 
class  StateSpace
 An OMPL state space for robowflex::darts::World. Can do motion planning for any of the robots or structures in the world. More...
 
class  Structure
 Wrapper class for a dart::dynamics::Skeleton. More...
 
class  TSR
 A Task Space Region (TSR). TSRs are workspace regions that impose a constraints on a robot. They are composed of a pose (in some reference frame) and tolerances on position and rotation. initialize() must be called once all parameters are set. More...
 
class  TSRSet
 Manager for a set of TSR constraints. Attempts to reduce redundancy and combines errors and Jacobians together. More...
 
class  TSRConstraint
 An OMPL constraint for TSRs. Under the hood, creates a TSRSet that is used for all computation. Make sure that the robot state space has all groups setup before creation of this constraint. More...
 
class  DistanceCollisionWrapper
 A wrapper for the ACM to pass into signed distance computation. Returns based on if the objects would collide. More...
 
class  World
 Wrapper for a dart::simulation::World, which contains a set of skeletons (i.e., Robots and Structures). The World is the main object that is used by motion planning as it contains a holistic view of the scene. More...
 

Typedefs

using ButtonCallback = std::function< void()>
 Callback function upon a button press. More...
 
using RenderCallback = std::function< void()>
 Callback upon a render call. More...
 

Functions

std::string generateUUID ()
 Generate a unique identifier. More...
 
RobotPtr loadMoveItRobot (const std::string &name, const std::string &urdf, const std::string &srdf)
 Load a robot from a URDF and SRDF (i.e., a MoveIt enabled robot). More...
 
dart::dynamics::ShapePtr makeGeometry (const GeometryPtr &geometry)
 Convert a robowflex::Geometry to a Dart Shape. More...
 
std::shared_ptr< dart::dynamics::BoxShape > makeBox (const Eigen::Ref< const Eigen::Vector3d > &v)
 Create a box. More...
 
std::shared_ptr< dart::dynamics::BoxShape > makeBox (double x, double y, double z)
 Create a box. More...
 
std::shared_ptr< dart::dynamics::CylinderShape > makeCylinder (double radius, double height)
 Create a cylinder. More...
 
std::shared_ptr< dart::dynamics::SphereShape > makeSphere (double radius)
 Create a sphere. More...
 
std::shared_ptr< dart::dynamics::MeshShape > makeMesh (const GeometryPtr &geometry)
 Create a mesh from a robowflex::Geometry that contains a mesh. More...
 
std::shared_ptr< dart::dynamics::MeshShape > makeArcsegment (double low, double high, double inner_radius, double outer_radius, std::size_t resolution=32)
 Create a circle's arcsector from one angle to another, with a specified radius. More...
 
void setColor (dart::dynamics::BodyNode *node, const Eigen::Vector4d &color)
 Sets the color of the shapes on a body node. More...
 

Detailed Description

DART-based robot modeling and planning.

Typedef Documentation

◆ ButtonCallback

Callback function upon a button press.

Definition at line 285 of file gui.h.

◆ RenderCallback

Callback upon a render call.

Definition at line 306 of file gui.h.

Function Documentation

◆ generateUUID()

std::string robowflex::darts::generateUUID ( )

Generate a unique identifier.

Returns
A random unique ID.

Definition at line 17 of file gui.cpp.

18 {
19  boost::uuids::random_generator gen;
20  boost::uuids::uuid u = gen();
21  return boost::lexical_cast<std::string>(u);
22 }

◆ loadMoveItRobot()

RobotPtr robowflex::darts::loadMoveItRobot ( const std::string name,
const std::string urdf,
const std::string srdf 
)

Load a robot from a URDF and SRDF (i.e., a MoveIt enabled robot).

Parameters
[in]nameName of the robot.
[in]urdfURDF URI.
[in]srdfSRDF URI.
Returns
The loaded robot.

Definition at line 586 of file robowflex_dart/src/robot.cpp.

588 {
589  auto robot = std::make_shared<Robot>(name);
590  robot->loadURDF(urdf);
591  robot->loadSRDF(srdf);
592 
593  return robot;
594 }
Functions for loading and animating robots in Blender.

◆ makeArcsegment()

std::shared_ptr< dart::dynamics::MeshShape > robowflex::darts::makeArcsegment ( double  low,
double  high,
double  inner_radius,
double  outer_radius,
std::size_t  resolution = 32 
)

Create a circle's arcsector from one angle to another, with a specified radius.

Parameters
[in]lowLower bound, in radians.
[in]highUpper bound, in radians.
[in]inner_radiusInner segment radius.
[in]outer_radiusOuter segment radius.
[in]resolutionNumber of segments.
Returns
The mesh shape.

Definition at line 419 of file structure.cpp.

423 {
424  if (resolution < 1)
425  throw std::runtime_error("Invalid resolution.");
426 
427  if (inner_radius > outer_radius)
428  throw std::runtime_error("Invalid radii.");
429 
430  if (low > high)
431  low = high;
432 
433  const double interval = high - low;
434  const double step = interval / resolution;
435 
436  auto *mesh = new aiMesh;
437  mesh->mMaterialIndex = (unsigned int)(-1);
438 
439  // number of segments, *2 for inner & outer, *2 for front & back
440  const std::size_t n_seg = resolution + 1;
441  const std::size_t n_v_face = n_seg * 2;
442  const std::size_t n_vert = n_v_face * 2;
443 
444  const std::size_t n_face = resolution * 2;
445 
446  mesh->mNumVertices = n_vert;
447  mesh->mVertices = new aiVector3D[n_vert];
448  mesh->mNormals = new aiVector3D[n_vert];
449  mesh->mColors[0] = new aiColor4D[n_vert];
450 
451  const double vx = 0;
452  aiVector3D vertex;
453 
454  const aiVector3D fnormal(1.0f, 0.0f, 0.0f);
455  const aiVector3D bnormal(-1.0f, 0.0f, 0.0f);
456  const aiColor4D color(0.0f, 0.0f, 0.0f, 1.0f);
457 
458  // Vertices
459  for (std::size_t i = 0; i <= resolution; ++i)
460  {
461  const double theta = low + step * i;
462 
463  // Inner Radius
464  const double yi = inner_radius * std::cos(theta);
465  const double zi = inner_radius * std::sin(theta);
466  vertex.Set(vx, yi, zi);
467 
468  // front
469  const std::size_t ifv = 2 * i;
470  mesh->mVertices[ifv] = vertex;
471  mesh->mNormals[ifv] = fnormal;
472  mesh->mColors[0][ifv] = color;
473 
474  // back
475  const std::size_t ibv = ifv + n_v_face;
476  mesh->mVertices[ibv] = vertex;
477  mesh->mNormals[ibv] = bnormal;
478  mesh->mColors[0][ibv] = color;
479 
480  // Outer Radius
481  const double yo = outer_radius * std::cos(theta);
482  const double zo = outer_radius * std::sin(theta);
483  vertex.Set(vx, yo, zo);
484 
485  // front
486  const std::size_t ofv = ifv + 1;
487  mesh->mVertices[ofv] = vertex;
488  mesh->mNormals[ofv] = fnormal;
489  mesh->mColors[0][ofv] = color;
490 
491  // back
492  const std::size_t obv = ofv + n_v_face;
493  mesh->mVertices[obv] = vertex;
494  mesh->mNormals[obv] = bnormal;
495  mesh->mColors[0][obv] = color;
496  }
497 
498  mesh->mNumFaces = n_face;
499  mesh->mFaces = new aiFace[n_face];
500 
501  // Faces
502  for (std::size_t i = 1; i <= resolution; ++i)
503  {
504  // front
505  const std::size_t ifv = 2 * i;
506  const std::size_t ifvp = 2 * (i - 1);
507  const std::size_t ofv = ifv + 1;
508  const std::size_t ofvp = ifvp + 1;
509 
510  aiFace *fface = &mesh->mFaces[i - 1];
511  fface->mNumIndices = 4;
512  fface->mIndices = new unsigned int[4];
513  fface->mIndices[0] = ifv;
514  fface->mIndices[1] = ifvp;
515  fface->mIndices[2] = ofvp;
516  fface->mIndices[3] = ofv;
517 
518  // back
519  const std::size_t ibv = ifv + n_v_face;
520  const std::size_t ibvp = ifvp + n_v_face;
521  const std::size_t obv = ofv + n_v_face;
522  const std::size_t obvp = ofvp + n_v_face;
523 
524  aiFace *bface = &mesh->mFaces[i + resolution - 1];
525  bface->mNumIndices = 4;
526  bface->mIndices = new unsigned int[4];
527  bface->mIndices[0] = obv;
528  bface->mIndices[1] = obvp;
529  bface->mIndices[2] = ibvp;
530  bface->mIndices[3] = ibv;
531  }
532 
533  auto *node = new aiNode;
534  node->mNumMeshes = 1;
535  node->mMeshes = new unsigned int[1];
536  node->mMeshes[0] = 0;
537 
538  auto *scene = new aiScene;
539  scene->mNumMeshes = 1;
540  scene->mMeshes = new aiMesh *[1];
541  scene->mMeshes[0] = mesh;
542  scene->mRootNode = node;
543 
544  auto shape = std::make_shared<dart::dynamics::MeshShape>(Eigen::Vector3d::Ones(), scene);
545  shape->setColorMode(dart::dynamics::MeshShape::SHAPE_COLOR);
546 
547  return shape;
548 }
T cos(T... args)
Functions for loading and animating scenes in Blender.
T sin(T... args)

◆ makeBox() [1/2]

std::shared_ptr< dart::dynamics::BoxShape > robowflex::darts::makeBox ( const Eigen::Ref< const Eigen::Vector3d > &  v)

Create a box.

Parameters
[in]vDimensions of the box.
Returns
The box shape.

Definition at line 370 of file structure.cpp.

371 {
372  return std::make_shared<dart::dynamics::BoxShape>(v);
373 }

◆ makeBox() [2/2]

std::shared_ptr< dart::dynamics::BoxShape > robowflex::darts::makeBox ( double  x,
double  y,
double  z 
)

Create a box.

Parameters
[in]xX dimension of box.
[in]yY dimension of box.
[in]zZ dimension of box.
Returns
The box shape.

Definition at line 375 of file structure.cpp.

376 {
377  return makeBox(Eigen::Vector3d{x, y, z});
378 }
std::shared_ptr< dart::dynamics::BoxShape > makeBox(const Eigen::Ref< const Eigen::Vector3d > &v)
Create a box.
Definition: structure.cpp:370

◆ makeCylinder()

std::shared_ptr< dart::dynamics::CylinderShape > robowflex::darts::makeCylinder ( double  radius,
double  height 
)

Create a cylinder.

Parameters
[in]radiusRadius of cylinder.
[in]heightHeight of the cylinder.
Returns
The cylinder shape.

Definition at line 380 of file structure.cpp.

381 {
382  return std::make_shared<dart::dynamics::CylinderShape>(radius, height);
383 }

◆ makeGeometry()

dart::dynamics::ShapePtr robowflex::darts::makeGeometry ( const GeometryPtr geometry)

Convert a robowflex::Geometry to a Dart Shape.

Parameters
[in]geometryGeometry to convert.
Returns
Shape from geometry.

Definition at line 348 of file structure.cpp.

349 {
350  const auto &dimensions = geometry->getDimensions();
351 
352  switch (geometry->getType())
353  {
354  case Geometry::ShapeType::BOX:
355  return makeBox(dimensions);
356  case Geometry::ShapeType::SPHERE:
357  return makeSphere(dimensions[0]);
358  case Geometry::ShapeType::CYLINDER:
359  return makeCylinder(dimensions[0], dimensions[1]);
360  case Geometry::ShapeType::MESH:
361  return makeMesh(geometry);
362  default:
363  break;
364  }
365 
366  return nullptr;
367 }
std::shared_ptr< dart::dynamics::CylinderShape > makeCylinder(double radius, double height)
Create a cylinder.
Definition: structure.cpp:380
std::shared_ptr< dart::dynamics::SphereShape > makeSphere(double radius)
Create a sphere.
Definition: structure.cpp:385
std::shared_ptr< dart::dynamics::MeshShape > makeMesh(const GeometryPtr &geometry)
Create a mesh from a robowflex::Geometry that contains a mesh.
Definition: structure.cpp:390

◆ makeMesh()

std::shared_ptr< dart::dynamics::MeshShape > robowflex::darts::makeMesh ( const GeometryPtr geometry)

Create a mesh from a robowflex::Geometry that contains a mesh.

Parameters
[in]geometryGeometry with a mesh to convert.
Returns
The mesh shape.

Definition at line 390 of file structure.cpp.

391 {
392  std::string uri = geometry->getResource();
393  Eigen::Vector3d dimensions = geometry->getDimensions();
394 
395  if (uri.empty())
396  {
397  const auto &temp_file_name = ".robowflex_tmp.stl";
398 
399  auto shape = std::dynamic_pointer_cast<shapes::Mesh>(geometry->getShape());
400 
401  std::vector<char> buffer;
402  shapes::writeSTLBinary(shape.get(), buffer);
403 
404  std::ofstream out;
405  out.open(temp_file_name, std::ofstream::out | std::ofstream::binary);
406  out.write(buffer.data(), buffer.size());
407  out.close();
408 
409  uri = temp_file_name;
410  }
411 
412  const auto &file = robowflex::IO::resolvePackage(uri);
413  const auto &aiscene = dart::dynamics::MeshShape::loadMesh(file);
414 
415  auto mesh = std::make_shared<dart::dynamics::MeshShape>(dimensions, aiscene);
416  return mesh;
417 }
T close(T... args)
T data(T... args)
T empty(T... args)
std::string resolvePackage(const std::string &path)
Resolves package:// URLs to their canonical form. The path does not need to exist,...
T open(T... args)
T size(T... args)
T write(T... args)

◆ makeSphere()

std::shared_ptr< dart::dynamics::SphereShape > robowflex::darts::makeSphere ( double  radius)

Create a sphere.

Parameters
[in]radiusRadius of sphere.
Returns
The sphere shape.

Definition at line 385 of file structure.cpp.

386 {
387  return std::make_shared<dart::dynamics::SphereShape>(radius);
388 }

◆ setColor()

void robowflex::darts::setColor ( dart::dynamics::BodyNode *  node,
const Eigen::Vector4d &  color 
)

Sets the color of the shapes on a body node.

Parameters
[in]nodeNode to set color of.
[in]colorColor to set.

Definition at line 550 of file structure.cpp.

551 {
552  for (const auto &shape : node->getShapeNodes())
553  shape->getVisualAspect()->setColor(color);
554 }