Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
tesseract_scene_graph Namespace Reference

Namespaces

namespace  test_suite
 

Classes

class  Collision
 
class  Inertial
 
class  Joint
 
class  JointCalibration
 
class  JointDynamics
 
class  JointLimits
 
class  JointMimic
 
class  JointSafety
 Parameters for Joint Safety Controllers. More...
 
struct  kdl_sub_tree_builder
 Every time a vertex is visited for the first time add a new segment to the KDL Tree;. More...
 
struct  kdl_tree_builder
 Every time a vertex is visited for the first time add a new segment to the KDL Tree;. More...
 
class  KDLStateSolver
 
struct  KDLTreeData
 The KDLTreeData populated when parsing scene graph. More...
 
class  Link
 
class  Material
 
class  MutableStateSolver
 A mutable state solver allows you to reconfigure the solver's links and joints. More...
 
struct  ofkt_builder
 Every time a vertex is visited for the first time add a new node to the tree. More...
 
class  OFKTBaseNode
 
class  OFKTContinuousNode
 
class  OFKTFixedNode
 
class  OFKTNode
 The OFKT node is contains multiple trasformation which are described below. More...
 
class  OFKTPrismaticNode
 
class  OFKTRevoluteNode
 
class  OFKTRootNode
 
class  OFKTStateSolver
 An implementation of the Optimized Forward Kinematic Tree as a stat solver. More...
 
class  SceneGraph
 
struct  SceneState
 This holds a state of the scene. More...
 
struct  ShortestPath
 Holds the shortest path information. More...
 
class  StateSolver
 
struct  ugraph_vertex_copier
 
class  Visual
 

Typedefs

using GraphProperty = boost::property< boost::graph_name_t, std::string, boost::property< boost::graph_root_t, std::string > >
 Defines the boost graph property. More...
 
using VertexProperty = boost::property< boost::vertex_link_t, Link::Ptr, boost::property< boost::vertex_link_visible_t, bool, boost::property< boost::vertex_link_collision_enabled_t, bool > > >
 Defines the boost graph vertex property. More...
 
using EdgeProperty = boost::property< boost::edge_joint_t, Joint::Ptr, boost::property< boost::edge_weight_t, double > >
 EdgeProperty. More...
 
using Graph = boost::adjacency_list< boost::listS, boost::listS, boost::bidirectionalS, VertexProperty, EdgeProperty, GraphProperty >
 
using UGraph = boost::adjacency_list< boost::listS, boost::listS, boost::undirectedS, VertexProperty, EdgeProperty, GraphProperty >
 

Enumerations

enum class  JointType {
  UNKNOWN , REVOLUTE , CONTINUOUS , PRISMATIC ,
  FLOATING , PLANAR , FIXED
}
 

Functions

std::ostream & operator<< (std::ostream &os, const ShortestPath &path)
 
std::ostream & operator<< (std::ostream &os, const JointType &type)
 
KDL::Frame convert (const Eigen::Isometry3d &transform)
 Convert Eigen::Isometry3d to KDL::Frame. More...
 
Eigen::Isometry3d convert (const KDL::Frame &frame)
 Convert KDL::Frame to Eigen::Isometry3d. More...
 
KDL::Vector convert (const Eigen::Vector3d &vector)
 Convert Eigen::Vector3d to KDL::Vector. More...
 
Eigen::Vector3d convert (const KDL::Vector &vector)
 Convert KDL::Vector to Eigen::Vector3d. More...
 
Eigen::MatrixXd convert (const KDL::Jacobian &jacobian)
 Convert KDL::Jacobian to Eigen::Matrix. More...
 
KDL::Jacobian convert (const Eigen::MatrixXd &jacobian)
 Convert Eigen::Matrix to KDL::Jacobian. More...
 
Eigen::MatrixXd convert (const KDL::Jacobian &jacobian, const std::vector< int > &q_nrs)
 Convert a subset of KDL::Jacobian to Eigen::Matrix. More...
 
KDL::Joint convert (const Joint::ConstPtr &joint)
 Convert Tesseract Joint to KDL Joint. More...
 
KDL::RigidBodyInertia convert (const Inertial::ConstPtr &inertial)
 Convert Tesseract Inertail to KDL Inertial. More...
 
KDLTreeData parseSceneGraph (const SceneGraph &scene_graph)
 Convert a Tesseract SceneGraph into a KDL Tree. More...
 
KDLTreeData parseSceneGraph (const SceneGraph &scene_graph, const std::vector< std::string > &joint_names, const std::unordered_map< std::string, double > &joint_values)
 Convert a portion of a Tesseract SceneGraph into a KDL Tree. More...
 

Variables

static const auto DEFAULT_TESSERACT_MATERIAL = std::make_shared<Material>("default_tesseract_material")
 

Typedef Documentation

◆ EdgeProperty

using tesseract_scene_graph::EdgeProperty = typedef boost::property<boost::edge_joint_t, Joint::Ptr, boost::property<boost::edge_weight_t, double> >

EdgeProperty.

The edge_weight represents the distance between the two links

◆ Graph

using tesseract_scene_graph::Graph = typedef boost:: adjacency_list<boost::listS, boost::listS, boost::bidirectionalS, VertexProperty, EdgeProperty, GraphProperty>

◆ GraphProperty

using tesseract_scene_graph::GraphProperty = typedef boost::property<boost::graph_name_t, std::string, boost::property<boost::graph_root_t, std::string> >

Defines the boost graph property.

◆ UGraph

using tesseract_scene_graph::UGraph = typedef boost::adjacency_list<boost::listS, boost::listS, boost::undirectedS, VertexProperty, EdgeProperty, GraphProperty>

◆ VertexProperty

using tesseract_scene_graph::VertexProperty = typedef boost::property< boost::vertex_link_t, Link::Ptr, boost::property<boost::vertex_link_visible_t, bool, boost::property<boost::vertex_link_collision_enabled_t, bool> >>

Defines the boost graph vertex property.

Enumeration Type Documentation

◆ JointType

Enumerator
UNKNOWN 
REVOLUTE 
CONTINUOUS 
PRISMATIC 
FLOATING 
PLANAR 
FIXED 

Function Documentation

◆ convert() [1/9]

KDL::Frame tesseract_scene_graph::convert ( const Eigen::Isometry3d &  transform)

Convert Eigen::Isometry3d to KDL::Frame.

Parameters
transformInput Eigen transform (Isometry3d)
Returns
frame Output KDL Frame

◆ convert() [2/9]

KDL::Jacobian tesseract_scene_graph::convert ( const Eigen::MatrixXd &  jacobian)

Convert Eigen::Matrix to KDL::Jacobian.

Parameters
jacobianInput Eigen MatrixXd
Returns
KDL Jacobian

◆ convert() [3/9]

KDL::Vector tesseract_scene_graph::convert ( const Eigen::Vector3d &  vector)

Convert Eigen::Vector3d to KDL::Vector.

Parameters
vectorInput Eigen Vector3d
Returns
vector Output KDL Vector

◆ convert() [4/9]

KDL::RigidBodyInertia tesseract_scene_graph::convert ( const Inertial::ConstPtr inertial)

Convert Tesseract Inertail to KDL Inertial.

Parameters
inertial
Returns

◆ convert() [5/9]

KDL::Joint tesseract_scene_graph::convert ( const Joint::ConstPtr joint)

Convert Tesseract Joint to KDL Joint.

Parameters
jointTesseract Joint
Returns
A KDL Joint

◆ convert() [6/9]

Eigen::Isometry3d tesseract_scene_graph::convert ( const KDL::Frame &  frame)

Convert KDL::Frame to Eigen::Isometry3d.

Parameters
frameInput KDL Frame
Returns
Eigen transform (Isometry3d)

◆ convert() [7/9]

Eigen::MatrixXd tesseract_scene_graph::convert ( const KDL::Jacobian &  jacobian)

Convert KDL::Jacobian to Eigen::Matrix.

Parameters
jacobianInput KDL Jacobian
Returns
Eigen MatrixXd

◆ convert() [8/9]

Eigen::MatrixXd tesseract_scene_graph::convert ( const KDL::Jacobian &  jacobian,
const std::vector< int > &  q_nrs 
)

Convert a subset of KDL::Jacobian to Eigen::Matrix.

Parameters
jacobianInput KDL Jacobian
q_nrsInput the columns to use
Returns
Eigen MatrixXd

◆ convert() [9/9]

Eigen::Vector3d tesseract_scene_graph::convert ( const KDL::Vector &  vector)

Convert KDL::Vector to Eigen::Vector3d.

Parameters
transformInput KDL Vector
Returns
frame Output Eigen Vector3d

◆ operator<<() [1/2]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const JointType type 
)
inline

◆ operator<<() [2/2]

std::ostream & tesseract_scene_graph::operator<< ( std::ostream &  os,
const ShortestPath path 
)
inline

◆ parseSceneGraph() [1/2]

KDLTreeData tesseract_scene_graph::parseSceneGraph ( const SceneGraph scene_graph)

Convert a Tesseract SceneGraph into a KDL Tree.

Exceptions
Ifgraph is not a tree
Parameters
scene_graphThe Tesseract Scene Graph
treeThe KDL Tree to populate.
Returns
Returns KDL tree data representation of the scene graph

◆ parseSceneGraph() [2/2]

KDLTreeData tesseract_scene_graph::parseSceneGraph ( const SceneGraph scene_graph,
const std::vector< std::string > &  joint_names,
const std::unordered_map< std::string, double > &  joint_values 
)

Convert a portion of a Tesseract SceneGraph into a KDL Tree.

This will create a new tree from multiple sub tree defined by the provided joint names The values are used to convert non fixed joints that are not listed in joint_names to a fixed joint. The first tree found a link is defined attaching world to the base link and all other trees are attached to this link by a fixed joint.

Exceptions
Ifgraph is not a tree it will return false.
Parameters
scene_graphThe Tesseract Scene Graph
treeThe KDL Tree to populate.
Returns
Returns KDL tree representation of the sub scene graph

Variable Documentation

◆ DEFAULT_TESSERACT_MATERIAL

const auto tesseract_scene_graph::DEFAULT_TESSERACT_MATERIAL = std::make_shared<Material>("default_tesseract_material")
static