Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Classes | Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
tesseract_scene_graph::SceneGraph Class Reference

#include <graph.h>

Inheritance diagram for tesseract_scene_graph::SceneGraph:
Inheritance graph
[legend]
Collaboration diagram for tesseract_scene_graph::SceneGraph:
Collaboration graph
[legend]

Classes

struct  adjacency_detector
 
struct  children_detector
 
struct  cycle_detector
 
struct  tree_detector
 

Public Types

using Vertex = SceneGraph::vertex_descriptor
 
using Edge = SceneGraph::edge_descriptor
 
using Ptr = std::shared_ptr< SceneGraph >
 
using ConstPtr = std::shared_ptr< const SceneGraph >
 
using UPtr = std::unique_ptr< SceneGraph >
 
using ConstUPtr = std::unique_ptr< const SceneGraph >
 

Public Member Functions

 SceneGraph (const std::string &name="")
 
 ~SceneGraph ()=default
 
 SceneGraph (const SceneGraph &other)=delete
 
SceneGraphoperator= (const SceneGraph &other)=delete
 
 SceneGraph (SceneGraph &&other) noexcept
 
SceneGraphoperator= (SceneGraph &&other) noexcept
 
SceneGraph::UPtr clone () const
 Clone the scene graph. More...
 
void clear ()
 Clear the scene graph. More...
 
void setName (const std::string &name)
 Sets the graph name. More...
 
const std::string & getName () const
 Sets the graph name. More...
 
bool setRoot (const std::string &name)
 Sets the root link name (aka. World Coordinate Frame) More...
 
const std::string & getRoot () const
 Gets the root link name (aka. World Coordinate Frame) More...
 
bool addLink (const Link &link, bool replace_allowed=false)
 Adds a link to the graph. More...
 
bool addLink (const Link &link, const Joint &joint)
 Adds a link/joint to the graph. More...
 
Link::ConstPtr getLink (const std::string &name) const
 Get a link in the graph. More...
 
std::vector< Link::ConstPtrgetLinks () const
 Get a vector links in the scene graph. More...
 
std::vector< Link::ConstPtrgetLeafLinks () const
 Get a vector leaf links in the scene graph. More...
 
bool removeLink (const std::string &name, bool recursive=false)
 Removes a link from the graph. More...
 
bool moveLink (const Joint &joint)
 Move link defined by provided joint This deletes all inbound joints on the parent link defined by the joint. More...
 
void setLinkVisibility (const std::string &name, bool visibility)
 Set a links visibility. More...
 
bool getLinkVisibility (const std::string &name) const
 Get a given links visibility setting. More...
 
void setLinkCollisionEnabled (const std::string &name, bool enabled)
 Set whether a link should be considered during collision checking. More...
 
bool getLinkCollisionEnabled (const std::string &name) const
 Get whether a link should be considered during collision checking. More...
 
bool addJoint (const Joint &joint)
 Adds joint to the graph. More...
 
Joint::ConstPtr getJoint (const std::string &name) const
 Get a joint in the graph. More...
 
bool removeJoint (const std::string &name, bool recursive=false)
 Removes a joint from the graph. More...
 
bool moveJoint (const std::string &name, const std::string &parent_link)
 Move joint to new parent link. More...
 
std::vector< Joint::ConstPtrgetJoints () const
 Get a vector of joints in the scene graph. More...
 
std::vector< Joint::ConstPtrgetActiveJoints () const
 Get a vector of active joints in the scene graph. More...
 
bool changeJointOrigin (const std::string &name, const Eigen::Isometry3d &new_origin)
 Changes the "origin" transform of the joint and recomputes the associated edge. More...
 
bool changeJointLimits (const std::string &name, const JointLimits &limits)
 Changes the limits of a joint. The JointLimits::Ptr remains the same, but the values passed in are assigned. More...
 
bool changeJointPositionLimits (const std::string &name, double lower, double upper)
 Changes the position limits associated with a joint. More...
 
bool changeJointVelocityLimits (const std::string &name, double limit)
 Changes the velocity limits associated with a joint. More...
 
bool changeJointAccelerationLimits (const std::string &name, double limit)
 Changes the acceleration limits associated with a joint. More...
 
JointLimits::ConstPtr getJointLimits (const std::string &name)
 Gets the limits of the joint specified by name. More...
 
void addAllowedCollision (const std::string &link_name1, const std::string &link_name2, const std::string &reason)
 Disable collision between two collision objects. More...
 
void removeAllowedCollision (const std::string &link_name1, const std::string &link_name2)
 Remove disabled collision pair from allowed collision matrix. More...
 
void removeAllowedCollision (const std::string &link_name)
 Remove disabled collision for any pair with link_name from allowed collision matrix. More...
 
void clearAllowedCollisions ()
 Remove all allowed collisions. More...
 
bool isCollisionAllowed (const std::string &link_name1, const std::string &link_name2) const
 Check if two links are allowed to be in collision. More...
 
tesseract_common::AllowedCollisionMatrix::ConstPtr getAllowedCollisionMatrix () const
 Get the allowed collision matrix. More...
 
tesseract_common::AllowedCollisionMatrix::Ptr getAllowedCollisionMatrix ()
 Get the allowed collision matrix. More...
 
Link::ConstPtr getSourceLink (const std::string &joint_name) const
 Get the source link (parent link) for a joint. More...
 
Link::ConstPtr getTargetLink (const std::string &joint_name) const
 Get the target link (child link) for a joint. More...
 
std::vector< Joint::ConstPtrgetInboundJoints (const std::string &link_name) const
 Get inbound joints for a link. More...
 
std::vector< Joint::ConstPtrgetOutboundJoints (const std::string &link_name) const
 Get outbound joints for a link. More...
 
bool isAcyclic () const
 Determine if the graph contains cycles. More...
 
bool isTree () const
 Determine if the graph is a tree. More...
 
bool isEmpty () const
 Check if the graph is empty. More...
 
std::vector< std::string > getAdjacentLinkNames (const std::string &name) const
 Get a vector of adjacent link names provided a link name. More...
 
std::vector< std::string > getInvAdjacentLinkNames (const std::string &name) const
 Geta a vectpr pf inverse adjacent link names provided a link name. More...
 
std::vector< std::string > getLinkChildrenNames (const std::string &name) const
 Get all children for a given link name. More...
 
std::vector< std::string > getJointChildrenNames (const std::string &name) const
 Get all children link names for a given joint name. More...
 
std::unordered_map< std::string, std::string > getAdjacencyMap (const std::vector< std::string > &link_names) const
 Create mapping between links in the scene to the provided links if they are directly affected if the link moves. More...
 
std::vector< std::string > getJointChildrenNames (const std::vector< std::string > &names) const
 Get all children link names for the given joint names. More...
 
void saveDOT (const std::string &path) const
 Saves Graph as Graph Description Language (DOT) More...
 
ShortestPath getShortestPath (const std::string &root, const std::string &tip) const
 Get the shortest path between two links. More...
 
Vertex getVertex (const std::string &name) const
 Get the graph vertex by name. More...
 
Edge getEdge (const std::string &name) const
 Get the graph edge by name. More...
 
bool insertSceneGraph (const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &prefix="")
 Merge a graph into the current graph. More...
 
bool insertSceneGraph (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::Joint &joint, const std::string &prefix="")
 Merge a graph into the current environment. More...
 
bool operator== (const SceneGraph &rhs) const
 
bool operator!= (const SceneGraph &rhs) const
 

Protected Member Functions

bool addLinkHelper (const Link::Ptr &link_ptr, bool replace_allowed=false)
 Adds a link to the graph. More...
 
bool addJointHelper (const Joint::Ptr &joint_ptr)
 Adds joint to the graph. More...
 

Private Member Functions

void rebuildLinkAndJointMaps ()
 The rebuild the link and joint map by extraction information from the graph. More...
 
std::vector< std::string > getLinkChildrenHelper (Vertex start_vertex) const
 Get the children of a vertex starting with start_vertex. More...
 
template<class Archive >
void save (Archive &ar, const unsigned int version) const
 
template<class Archive >
void load (Archive &ar, const unsigned int version)
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 

Private Attributes

std::unordered_map< std::string, std::pair< Link::Ptr, Vertex > > link_map_
 
std::unordered_map< std::string, std::pair< Joint::Ptr, Edge > > joint_map_
 
tesseract_common::AllowedCollisionMatrix::Ptr acm_
 

Friends

class boost::serialization::access
 

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Edge

using tesseract_scene_graph::SceneGraph::Edge = SceneGraph::edge_descriptor

◆ Ptr

◆ UPtr

◆ Vertex

using tesseract_scene_graph::SceneGraph::Vertex = SceneGraph::vertex_descriptor

Constructor & Destructor Documentation

◆ SceneGraph() [1/3]

tesseract_scene_graph::SceneGraph::SceneGraph ( const std::string &  name = "")

◆ ~SceneGraph()

tesseract_scene_graph::SceneGraph::~SceneGraph ( )
default

◆ SceneGraph() [2/3]

tesseract_scene_graph::SceneGraph::SceneGraph ( const SceneGraph other)
delete

◆ SceneGraph() [3/3]

tesseract_scene_graph::SceneGraph::SceneGraph ( SceneGraph &&  other)
noexcept

Member Function Documentation

◆ addAllowedCollision()

void tesseract_scene_graph::SceneGraph::addAllowedCollision ( const std::string &  link_name1,
const std::string &  link_name2,
const std::string &  reason 
)

Disable collision between two collision objects.

Parameters
link_name1Collision object name
link_name2Collision object name
reasonThe reason for disabling collision

◆ addJoint()

bool tesseract_scene_graph::SceneGraph::addJoint ( const Joint joint)

Adds joint to the graph.

Parameters
jointThe joint to be added
Returns
Return False if parent or child link does not exists and if joint name already exists in the graph, otherwise true

◆ addJointHelper()

bool tesseract_scene_graph::SceneGraph::addJointHelper ( const Joint::Ptr joint_ptr)
protected

Adds joint to the graph.

Parameters
joint_ptrShared pointer to the joint to be added
Returns
Return False if parent or child link does not exists and if joint name already exists in the graph, otherwise true

◆ addLink() [1/2]

bool tesseract_scene_graph::SceneGraph::addLink ( const Link link,
bool  replace_allowed = false 
)

Adds a link to the graph.

The first link added to the graph is set as the root by default. Use setRoot to change the root link of the graph.

Parameters
linkThe link to be added to the graph
replace_allowedIf true and the link exist it will be replaced
Returns
Return False if a link with the same name already exists and replace is not allowed, otherwise true

◆ addLink() [2/2]

bool tesseract_scene_graph::SceneGraph::addLink ( const Link link,
const Joint joint 
)

Adds a link/joint to the graph.

The first link added to the graph is set as the root by default. Use setRoot to change the root link of the graph.

Parameters
linkThe link to be added to the graph
jointThe associated joint to be added to the graph
Returns
Return False if a link with the same name allready exists, otherwise true

◆ addLinkHelper()

bool tesseract_scene_graph::SceneGraph::addLinkHelper ( const Link::Ptr link_ptr,
bool  replace_allowed = false 
)
protected

Adds a link to the graph.

The first link added to the graph is set as the root by default. Use setRoot to change the root link of the graph.

Parameters
link_ptrShared pointer to the link to be added to the graph
replace_allowedIf true and the link exist it will be replaced
Returns
Return False if a link with the same name already exists and replace is not allowed, otherwise true

◆ changeJointAccelerationLimits()

bool tesseract_scene_graph::SceneGraph::changeJointAccelerationLimits ( const std::string &  name,
double  limit 
)

Changes the acceleration limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
limitsNew acceleration limits to be set as the joint limits
Returns

◆ changeJointLimits()

bool tesseract_scene_graph::SceneGraph::changeJointLimits ( const std::string &  name,
const JointLimits limits 
)

Changes the limits of a joint. The JointLimits::Ptr remains the same, but the values passed in are assigned.

Parameters
nameName of the joint to be changed
limitsThe new limits associated with the joint
Returns
True if successful.

◆ changeJointOrigin()

bool tesseract_scene_graph::SceneGraph::changeJointOrigin ( const std::string &  name,
const Eigen::Isometry3d &  new_origin 
)

Changes the "origin" transform of the joint and recomputes the associated edge.

Parameters
nameName of the joint to be changed
new_originThe new transform associated with the joint
Returns
True if successful.

◆ changeJointPositionLimits()

bool tesseract_scene_graph::SceneGraph::changeJointPositionLimits ( const std::string &  name,
double  lower,
double  upper 
)

Changes the position limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
limitsNew position limits to be set as the joint limits @returnTrue if successful.

◆ changeJointVelocityLimits()

bool tesseract_scene_graph::SceneGraph::changeJointVelocityLimits ( const std::string &  name,
double  limit 
)

Changes the velocity limits associated with a joint.

Parameters
joint_nameName of the joint to be updated
limitsNew velocity limits to be set as the joint limits
Returns

◆ clear()

void tesseract_scene_graph::SceneGraph::clear ( )

Clear the scene graph.

◆ clearAllowedCollisions()

void tesseract_scene_graph::SceneGraph::clearAllowedCollisions ( )

Remove all allowed collisions.

◆ clone()

SceneGraph::UPtr tesseract_scene_graph::SceneGraph::clone ( ) const

Clone the scene graph.

Returns
The cloned scene graph

◆ getActiveJoints()

std::vector< Joint::ConstPtr > tesseract_scene_graph::SceneGraph::getActiveJoints ( ) const

Get a vector of active joints in the scene graph.

Returns
A vector of active joints

◆ getAdjacencyMap()

std::unordered_map< std::string, std::string > tesseract_scene_graph::SceneGraph::getAdjacencyMap ( const std::vector< std::string > &  link_names) const

Create mapping between links in the scene to the provided links if they are directly affected if the link moves.

Parameters
link_namesThe links to map other links to
Returns
A map of affected links to on of the provided link names.

◆ getAdjacentLinkNames()

std::vector< std::string > tesseract_scene_graph::SceneGraph::getAdjacentLinkNames ( const std::string &  name) const

Get a vector of adjacent link names provided a link name.

Parameters
nameName of link
Returns
A vector of adjacent link names

◆ getAllowedCollisionMatrix() [1/2]

tesseract_common::AllowedCollisionMatrix::Ptr tesseract_scene_graph::SceneGraph::getAllowedCollisionMatrix ( )

Get the allowed collision matrix.

Returns
AllowedCollisionMatrixPtr

◆ getAllowedCollisionMatrix() [2/2]

tesseract_common::AllowedCollisionMatrix::ConstPtr tesseract_scene_graph::SceneGraph::getAllowedCollisionMatrix ( ) const

Get the allowed collision matrix.

Returns
AllowedCollisionMatrixConstPtr

◆ getEdge()

SceneGraph::Edge tesseract_scene_graph::SceneGraph::getEdge ( const std::string &  name) const

Get the graph edge by name.

Parameters
nameThe edge/joint name
Returns
Graph Edge

◆ getInboundJoints()

std::vector< Joint::ConstPtr > tesseract_scene_graph::SceneGraph::getInboundJoints ( const std::string &  link_name) const

Get inbound joints for a link.

The inbound joints are all joints that have the link identified as the child link

Parameters
link_nameThe name of the link
Returns
Vector of joints

◆ getInvAdjacentLinkNames()

std::vector< std::string > tesseract_scene_graph::SceneGraph::getInvAdjacentLinkNames ( const std::string &  name) const

Geta a vectpr pf inverse adjacent link names provided a link name.

Parameters
name
Returns

◆ getJoint()

Joint::ConstPtr tesseract_scene_graph::SceneGraph::getJoint ( const std::string &  name) const

Get a joint in the graph.

Parameters
nameThe name of the joint
Returns
Return nullptr if joint name does not exists, otherwise a pointer to the joint

◆ getJointChildrenNames() [1/2]

std::vector< std::string > tesseract_scene_graph::SceneGraph::getJointChildrenNames ( const std::string &  name) const

Get all children link names for a given joint name.

Parameters
nameName of joint
Returns
A vector of child link names

◆ getJointChildrenNames() [2/2]

std::vector< std::string > tesseract_scene_graph::SceneGraph::getJointChildrenNames ( const std::vector< std::string > &  names) const

Get all children link names for the given joint names.

Todo:
Need to create custom visitor so already process joint_names do not get processed again.
Parameters
namesName of joints
Returns
A vector of child link names

◆ getJointLimits()

JointLimits::ConstPtr tesseract_scene_graph::SceneGraph::getJointLimits ( const std::string &  name)

Gets the limits of the joint specified by name.

Parameters
nameName of the joint which limits will be retrieved
Returns
Limits of the joint. Returns nullptr is joint is not found.

◆ getJoints()

std::vector< Joint::ConstPtr > tesseract_scene_graph::SceneGraph::getJoints ( ) const

Get a vector of joints in the scene graph.

Returns
A vector of joints

◆ getLeafLinks()

std::vector< Link::ConstPtr > tesseract_scene_graph::SceneGraph::getLeafLinks ( ) const

Get a vector leaf links in the scene graph.

Returns
A vector of links

◆ getLink()

Link::ConstPtr tesseract_scene_graph::SceneGraph::getLink ( const std::string &  name) const

Get a link in the graph.

Parameters
nameThe name of the link
Returns
Return nullptr if link name does not exists, otherwise a pointer to the link

◆ getLinkChildrenHelper()

std::vector< std::string > tesseract_scene_graph::SceneGraph::getLinkChildrenHelper ( Vertex  start_vertex) const
inlineprivate

Get the children of a vertex starting with start_vertex.

Note: This list will include the start vertex

Parameters
start_vertexThe vertex to find childeren for.
Returns
A list of child link names including the start vertex

◆ getLinkChildrenNames()

std::vector< std::string > tesseract_scene_graph::SceneGraph::getLinkChildrenNames ( const std::string &  name) const

Get all children for a given link name.

Parameters
nameName of Link
Returns
A vector of child link names

◆ getLinkCollisionEnabled()

bool tesseract_scene_graph::SceneGraph::getLinkCollisionEnabled ( const std::string &  name) const

Get whether a link should be considered during collision checking.

Returns
True if should be considered during collision checking, otherwise false

◆ getLinks()

std::vector< Link::ConstPtr > tesseract_scene_graph::SceneGraph::getLinks ( ) const

Get a vector links in the scene graph.

Returns
A vector of links

◆ getLinkVisibility()

bool tesseract_scene_graph::SceneGraph::getLinkVisibility ( const std::string &  name) const

Get a given links visibility setting.

Returns
True if should be visible, otherwise false

◆ getName()

const std::string & tesseract_scene_graph::SceneGraph::getName ( ) const

Sets the graph name.

Parameters
nameThe name of the graph

◆ getOutboundJoints()

std::vector< Joint::ConstPtr > tesseract_scene_graph::SceneGraph::getOutboundJoints ( const std::string &  link_name) const

Get outbound joints for a link.

The outbound joints are all joins that have the link identified as the parent link

Parameters
link_nameThe name of the link
Returns
Vector of joints

◆ getRoot()

const std::string & tesseract_scene_graph::SceneGraph::getRoot ( ) const

Gets the root link name (aka. World Coordinate Frame)

Returns
The root link name

◆ getShortestPath()

ShortestPath tesseract_scene_graph::SceneGraph::getShortestPath ( const std::string &  root,
const std::string &  tip 
) const

Get the shortest path between two links.

Parameters
rootThe base link
tipThe tip link
Returns
The shortest path between the two links

◆ getSourceLink()

Link::ConstPtr tesseract_scene_graph::SceneGraph::getSourceLink ( const std::string &  joint_name) const

Get the source link (parent link) for a joint.

Parameters
joint_nameThe name of the joint
Returns
The source link

◆ getTargetLink()

Link::ConstPtr tesseract_scene_graph::SceneGraph::getTargetLink ( const std::string &  joint_name) const

Get the target link (child link) for a joint.

Parameters
joint_nameThe name of the joint
Returns
The target link

◆ getVertex()

SceneGraph::Vertex tesseract_scene_graph::SceneGraph::getVertex ( const std::string &  name) const

Get the graph vertex by name.

Parameters
nameThe vertex/link name
Returns
Graph Vertex

◆ insertSceneGraph() [1/2]

bool tesseract_scene_graph::SceneGraph::insertSceneGraph ( const tesseract_scene_graph::SceneGraph scene_graph,
const std::string &  prefix = "" 
)

Merge a graph into the current graph.

Parameters
scene_graphConst ref to the graph to be merged (said graph will be copied)
prefixstring Will prepend to every link and joint of the merged graph
Returns
Return False if any link or joint name collides with current environment, otherwise True Merge a sub-graph into the current environment, considering that the root of the merged graph is attached to the root of the environment by a fixed joint and no displacement. Every joint and link of the sub-graph will be copied into the environment graph. The prefix argument is meant to allow adding multiple copies of the same sub-graph with different names

◆ insertSceneGraph() [2/2]

bool tesseract_scene_graph::SceneGraph::insertSceneGraph ( const tesseract_scene_graph::SceneGraph scene_graph,
const tesseract_scene_graph::Joint joint,
const std::string &  prefix = "" 
)

Merge a graph into the current environment.

Parameters
scene_graphConst ref to the graph to be merged (said graph will be copied)
jointThe joint that connects current environment with the inserted graph
prefixstring Will prepend to every link and joint of the merged graph
Returns
Return False if any link or joint name collides with current environment, otherwise True Merge a sub-graph into the current environment. Every joint and link of the sub-graph will be copied into the environment graph. The prefix argument is meant to allow adding multiple copies of the same sub-graph with different names

◆ isAcyclic()

bool tesseract_scene_graph::SceneGraph::isAcyclic ( ) const

Determine if the graph contains cycles.

Returns
True if graph is acyclic (no cycles) otherwise false

◆ isCollisionAllowed()

bool tesseract_scene_graph::SceneGraph::isCollisionAllowed ( const std::string &  link_name1,
const std::string &  link_name2 
) const

Check if two links are allowed to be in collision.

Parameters
link_name1link name
link_name2link name
Returns
True if the two links are allowed to be in collision, otherwise false

◆ isEmpty()

bool tesseract_scene_graph::SceneGraph::isEmpty ( ) const

Check if the graph is empty.

Returns
True if empty, otherwise false

◆ isTree()

bool tesseract_scene_graph::SceneGraph::isTree ( ) const

Determine if the graph is a tree.

Returns
True if graph is tree otherwise false

◆ load()

template<class Archive >
void tesseract_scene_graph::SceneGraph::load ( Archive &  ar,
const unsigned int  version 
)
private

◆ moveJoint()

bool tesseract_scene_graph::SceneGraph::moveJoint ( const std::string &  name,
const std::string &  parent_link 
)

Move joint to new parent link.

Parameters
nameName of the joint to move
parent_linkName of parent link to move to
Returns
Returns true if successful, otherwise false.

◆ moveLink()

bool tesseract_scene_graph::SceneGraph::moveLink ( const Joint joint)

Move link defined by provided joint This deletes all inbound joints on the parent link defined by the joint.

Parameters
jointThe joint defining the link move
Returns
Returns true if successful, otherwise false.

◆ operator!=()

bool tesseract_scene_graph::SceneGraph::operator!= ( const SceneGraph rhs) const

◆ operator=() [1/2]

SceneGraph & tesseract_scene_graph::SceneGraph::operator= ( const SceneGraph other)
delete

◆ operator=() [2/2]

SceneGraph & tesseract_scene_graph::SceneGraph::operator= ( SceneGraph &&  other)
noexcept

◆ operator==()

bool tesseract_scene_graph::SceneGraph::operator== ( const SceneGraph rhs) const

◆ rebuildLinkAndJointMaps()

void tesseract_scene_graph::SceneGraph::rebuildLinkAndJointMaps ( )
private

The rebuild the link and joint map by extraction information from the graph.

◆ removeAllowedCollision() [1/2]

void tesseract_scene_graph::SceneGraph::removeAllowedCollision ( const std::string &  link_name)

Remove disabled collision for any pair with link_name from allowed collision matrix.

Parameters
link_nameCollision object name

◆ removeAllowedCollision() [2/2]

void tesseract_scene_graph::SceneGraph::removeAllowedCollision ( const std::string &  link_name1,
const std::string &  link_name2 
)

Remove disabled collision pair from allowed collision matrix.

Parameters
link_name1Collision object name
link_name2Collision object name

◆ removeJoint()

bool tesseract_scene_graph::SceneGraph::removeJoint ( const std::string &  name,
bool  recursive = false 
)

Removes a joint from the graph.

Parameters
nameName of the joint to be removed
recursiveIf true all children are removed if this this is the only joint of the child link
Returns
Return False if a joint does not exists, otherwise true

◆ removeLink()

bool tesseract_scene_graph::SceneGraph::removeLink ( const std::string &  name,
bool  recursive = false 
)

Removes a link from the graph.

Note: this will remove all inbound and outbound edges

Parameters
nameName of the link to be removed
recursiveIf true all children are removed if it only has a single joint
Returns
Return False if a link does not exists, otherwise true

◆ save()

template<class Archive >
void tesseract_scene_graph::SceneGraph::save ( Archive &  ar,
const unsigned int  version 
) const
private

◆ saveDOT()

void tesseract_scene_graph::SceneGraph::saveDOT ( const std::string &  path) const

Saves Graph as Graph Description Language (DOT)

Parameters
pathThe file path

◆ serialize()

template<class Archive >
void tesseract_scene_graph::SceneGraph::serialize ( Archive &  ar,
const unsigned int  version 
)
private

◆ setLinkCollisionEnabled()

void tesseract_scene_graph::SceneGraph::setLinkCollisionEnabled ( const std::string &  name,
bool  enabled 
)

Set whether a link should be considered during collision checking.

Parameters
enabledTrue if should be considered during collision checking, otherwise false

◆ setLinkVisibility()

void tesseract_scene_graph::SceneGraph::setLinkVisibility ( const std::string &  name,
bool  visibility 
)

Set a links visibility.

Parameters
visibilityTrue if should be visible, otherwise false

◆ setName()

void tesseract_scene_graph::SceneGraph::setName ( const std::string &  name)

Sets the graph name.

Parameters
nameThe name of the graph

◆ setRoot()

bool tesseract_scene_graph::SceneGraph::setRoot ( const std::string &  name)

Sets the root link name (aka. World Coordinate Frame)

Parameters
nameThe name of the link
Returns
Return False if a link does not exists, otherwise true

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Member Data Documentation

◆ acm_

tesseract_common::AllowedCollisionMatrix::Ptr tesseract_scene_graph::SceneGraph::acm_
private

◆ joint_map_

std::unordered_map<std::string, std::pair<Joint::Ptr, Edge> > tesseract_scene_graph::SceneGraph::joint_map_
private

◆ link_map_

std::unordered_map<std::string, std::pair<Link::Ptr, Vertex> > tesseract_scene_graph::SceneGraph::link_map_
private

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