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]

Public Types

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

Public Member Functions

void addAllowedCollision (const std::string &link_name1, const std::string &link_name2, const std::string &reason)
 Disable collision between two collision objects. More...
 
bool addJoint (const Joint &joint)
 Adds joint to the graph. 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...
 
bool changeJointAccelerationLimits (const std::string &name, double limit)
 Changes the acceleration limits associated with a joint. More...
 
bool changeJointJerkLimits (const std::string &name, double limit)
 Changes the jerk limits associated with a joint. 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 changeJointOrigin (const std::string &name, const Eigen::Isometry3d &new_origin)
 Changes the "origin" transform of the joint and recomputes the associated edge. 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...
 
void clear ()
 Clear the scene graph. More...
 
void clearAllowedCollisions ()
 Remove all allowed collisions. More...
 
SceneGraph::UPtr clone () const
 Clone the scene graph. More...
 
std::vector< std::shared_ptr< const Joint > > getActiveJoints () const
 Get a vector of active joints in the scene graph. 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 > getAdjacentLinkNames (const std::string &name) const
 Get a vector of adjacent link names provided a link name. More...
 
std::shared_ptr< tesseract_common::AllowedCollisionMatrixgetAllowedCollisionMatrix ()
 Get the allowed collision matrix. More...
 
std::shared_ptr< const tesseract_common::AllowedCollisionMatrixgetAllowedCollisionMatrix () const
 Get the allowed collision matrix. More...
 
Edge getEdge (const std::string &name) const
 Get the graph edge by name. More...
 
std::vector< std::shared_ptr< const Joint > > getInboundJoints (const std::string &link_name) const
 Get inbound joints for a link. 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::shared_ptr< const JointgetJoint (const std::string &name) const
 Get a joint in the graph. More...
 
std::vector< std::string > getJointChildrenNames (const std::string &name) const
 Get all children link names for a given joint name. More...
 
std::vector< std::string > getJointChildrenNames (const std::vector< std::string > &names) const
 Get all children link names for the given joint names. More...
 
std::shared_ptr< const JointLimitsgetJointLimits (const std::string &name)
 Gets the limits of the joint specified by name. More...
 
std::vector< std::shared_ptr< const Joint > > getJoints () const
 Get a vector of joints in the scene graph. More...
 
std::vector< std::shared_ptr< const Link > > getLeafLinks () const
 Get a vector leaf links in the scene graph. More...
 
std::shared_ptr< const LinkgetLink (const std::string &name) const
 Get a link in the graph. More...
 
std::vector< std::string > getLinkChildrenNames (const std::string &name) const
 Get all children for a given link name. More...
 
bool getLinkCollisionEnabled (const std::string &name) const
 Get whether a link should be considered during collision checking. More...
 
std::vector< std::shared_ptr< const Link > > getLinks () const
 Get a vector links in the scene graph. More...
 
bool getLinkVisibility (const std::string &name) const
 Get a given links visibility setting. More...
 
const std::string & getName () const
 Sets the graph name. More...
 
std::vector< std::shared_ptr< const Joint > > getOutboundJoints (const std::string &link_name) const
 Get outbound joints for a link. More...
 
const std::string & getRoot () const
 Gets the root link name (aka. World Coordinate Frame) More...
 
ShortestPath getShortestPath (const std::string &root, const std::string &tip) const
 Get the shortest path between two links. More...
 
std::shared_ptr< const LinkgetSourceLink (const std::string &joint_name) const
 Get the source link (parent link) for a joint. More...
 
std::shared_ptr< const LinkgetTargetLink (const std::string &joint_name) const
 Get the target link (child link) for a joint. More...
 
Vertex getVertex (const std::string &name) const
 Get the graph vertex 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 isAcyclic () const
 Determine if the graph contains cycles. 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...
 
bool isEmpty () const
 Check if the graph is empty. More...
 
bool isTree () const
 Determine if the graph is a tree. More...
 
bool moveJoint (const std::string &name, const std::string &parent_link)
 Move joint to new parent link. 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...
 
bool operator!= (const SceneGraph &rhs) const
 
SceneGraphoperator= (const SceneGraph &other)=delete
 
SceneGraphoperator= (SceneGraph &&other) noexcept
 
bool operator== (const SceneGraph &rhs) const
 
void removeAllowedCollision (const std::string &link_name)
 Remove disabled collision for any pair with link_name from allowed collision matrix. More...
 
void removeAllowedCollision (const std::string &link_name1, const std::string &link_name2)
 Remove disabled collision pair from allowed collision matrix. More...
 
bool removeJoint (const std::string &name, bool recursive=false)
 Removes a joint from the graph. More...
 
bool removeLink (const std::string &name, bool recursive=false)
 Removes a link from the graph. More...
 
void saveDOT (const std::string &path) const
 Saves Graph as Graph Description Language (DOT) More...
 
 SceneGraph (const SceneGraph &other)=delete
 
 SceneGraph (const std::string &name="")
 
 SceneGraph (SceneGraph &&other) noexcept
 
void setAllowedCollisionMatrix (std::shared_ptr< tesseract_common::AllowedCollisionMatrix > acm)
 Set the allowed collision matrix. More...
 
void setLinkCollisionEnabled (const std::string &name, bool enabled)
 Set whether a link should be considered during collision checking. More...
 
void setLinkVisibility (const std::string &name, bool visibility)
 Set a links visibility. More...
 
void setName (const std::string &name)
 Sets the graph name. More...
 
bool setRoot (const std::string &name)
 Sets the root link name (aka. World Coordinate Frame) More...
 
 ~SceneGraph ()=default
 

Protected Member Functions

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

Private Member Functions

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

Private Attributes

std::shared_ptr< tesseract_common::AllowedCollisionMatrixacm_
 
std::unordered_map< std::string, std::pair< std::shared_ptr< Joint >, Edge > > joint_map_
 
std::unordered_map< std::string, std::pair< std::shared_ptr< Link >, Vertex > > link_map_
 

Friends

class boost::serialization::access
 
struct tesseract_common::Serialization
 

Detailed Description

Definition at line 125 of file graph.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 136 of file graph.h.

◆ ConstUPtr

Definition at line 138 of file graph.h.

◆ Edge

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

Definition at line 133 of file graph.h.

◆ Ptr

Definition at line 135 of file graph.h.

◆ UPtr

Definition at line 137 of file graph.h.

◆ Vertex

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

Definition at line 132 of file graph.h.

Constructor & Destructor Documentation

◆ SceneGraph() [1/3]

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

Definition at line 189 of file graph.cpp.

◆ ~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

Definition at line 194 of file graph.cpp.

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

Definition at line 777 of file graph.cpp.

◆ 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

Definition at line 460 of file graph.cpp.

◆ addJointHelper()

bool tesseract_scene_graph::SceneGraph::addJointHelper ( const std::shared_ptr< Joint > &  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

Definition at line 466 of file graph.cpp.

◆ 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

Definition at line 273 of file graph.cpp.

◆ 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

Definition at line 279 of file graph.cpp.

◆ addLinkHelper()

bool tesseract_scene_graph::SceneGraph::addLinkHelper ( const std::shared_ptr< Link > &  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

Definition at line 302 of file graph.cpp.

◆ 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

Definition at line 705 of file graph.cpp.

◆ changeJointJerkLimits()

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

Changes the jerk limits associated with a joint.

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

Definition at line 732 of file graph.cpp.

◆ 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.

Definition at line 631 of file graph.cpp.

◆ 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.

Definition at line 608 of file graph.cpp.

◆ 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.

Definition at line 661 of file graph.cpp.

◆ 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

Definition at line 684 of file graph.cpp.

◆ clear()

void tesseract_scene_graph::SceneGraph::clear ( )

Clear the scene graph.

Definition at line 238 of file graph.cpp.

◆ clearAllowedCollisions()

void tesseract_scene_graph::SceneGraph::clearAllowedCollisions ( )

Remove all allowed collisions.

Definition at line 791 of file graph.cpp.

◆ clone()

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

Clone the scene graph.

Returns
The cloned scene graph

Definition at line 216 of file graph.cpp.

◆ getActiveJoints()

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

Get a vector of active joints in the scene graph.

Returns
A vector of active joints

Definition at line 595 of file graph.cpp.

◆ 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.

Definition at line 948 of file graph.cpp.

◆ 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

Definition at line 897 of file graph.cpp.

◆ getAllowedCollisionMatrix() [1/2]

std::shared_ptr<tesseract_common::AllowedCollisionMatrix> tesseract_scene_graph::SceneGraph::getAllowedCollisionMatrix ( )

Get the allowed collision matrix.

Returns
AllowedCollisionMatrixPtr

◆ getAllowedCollisionMatrix() [2/2]

std::shared_ptr< tesseract_common::AllowedCollisionMatrix > tesseract_scene_graph::SceneGraph::getAllowedCollisionMatrix ( ) const

Get the allowed collision matrix.

Returns
AllowedCollisionMatrixConstPtr

Definition at line 798 of file graph.cpp.

◆ 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

Definition at line 1118 of file graph.cpp.

◆ getInboundJoints()

std::vector< std::shared_ptr< const Joint > > 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

Definition at line 819 of file graph.cpp.

◆ 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

Definition at line 907 of file graph.cpp.

◆ getJoint()

std::shared_ptr< const Joint > 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

Definition at line 525 of file graph.cpp.

◆ 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

Definition at line 927 of file graph.cpp.

◆ 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

Definition at line 935 of file graph.cpp.

◆ getJointLimits()

std::shared_ptr< const JointLimits > 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.

Definition at line 758 of file graph.cpp.

◆ getJoints()

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

Get a vector of joints in the scene graph.

Returns
A vector of joints

Definition at line 585 of file graph.cpp.

◆ getLeafLinks()

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

Get a vector leaf links in the scene graph.

Returns
A vector of links

Definition at line 351 of file graph.cpp.

◆ getLink()

std::shared_ptr< const Link > 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

Definition at line 332 of file graph.cpp.

◆ getLinkChildrenHelper()

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

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

Definition at line 1273 of file graph.cpp.

◆ 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

Definition at line 917 of file graph.cpp.

◆ 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

Definition at line 453 of file graph.cpp.

◆ getLinks()

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

Get a vector links in the scene graph.

Returns
A vector of links

Definition at line 341 of file graph.cpp.

◆ 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

Definition at line 439 of file graph.cpp.

◆ getName()

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

Sets the graph name.

Parameters
nameThe name of the graph

Definition at line 251 of file graph.cpp.

◆ getOutboundJoints()

std::vector< std::shared_ptr< const Joint > > 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

Definition at line 839 of file graph.cpp.

◆ getRoot()

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

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

Returns
The root link name

Definition at line 268 of file graph.cpp.

◆ 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

Definition at line 1008 of file graph.cpp.

◆ getSourceLink()

std::shared_ptr< const Link > 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

Definition at line 805 of file graph.cpp.

◆ getTargetLink()

std::shared_ptr< const Link > 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

Definition at line 812 of file graph.cpp.

◆ 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

Definition at line 1109 of file graph.cpp.

◆ 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

Definition at line 1158 of file graph.cpp.

◆ 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

Definition at line 1219 of file graph.cpp.

◆ isAcyclic()

bool tesseract_scene_graph::SceneGraph::isAcyclic ( ) const

Determine if the graph contains cycles.

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

Definition at line 861 of file graph.cpp.

◆ 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

Definition at line 793 of file graph.cpp.

◆ isEmpty()

bool tesseract_scene_graph::SceneGraph::isEmpty ( ) const

Check if the graph is empty.

Returns
True if empty, otherwise false

Definition at line 859 of file graph.cpp.

◆ isTree()

bool tesseract_scene_graph::SceneGraph::isTree ( ) const

Determine if the graph is a tree.

Returns
True if graph is tree otherwise false

Definition at line 879 of file graph.cpp.

◆ load()

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

Definition at line 1330 of file graph.cpp.

◆ 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.

Definition at line 557 of file graph.cpp.

◆ 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.

Definition at line 408 of file graph.cpp.

◆ operator!=()

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

Definition at line 1319 of file graph.cpp.

◆ 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

Definition at line 203 of file graph.cpp.

◆ operator==()

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

Definition at line 1299 of file graph.cpp.

◆ rebuildLinkAndJointMaps()

void tesseract_scene_graph::SceneGraph::rebuildLinkAndJointMaps ( )
private

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

Definition at line 1249 of file graph.cpp.

◆ 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

Definition at line 789 of file graph.cpp.

◆ 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

Definition at line 784 of file graph.cpp.

◆ 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

Definition at line 534 of file graph.cpp.

◆ 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

Definition at line 364 of file graph.cpp.

◆ save()

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

Definition at line 1322 of file graph.cpp.

◆ saveDOT()

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

Saves Graph as Graph Description Language (DOT)

Parameters
pathThe file path

Definition at line 977 of file graph.cpp.

◆ serialize()

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

Definition at line 1340 of file graph.cpp.

◆ setAllowedCollisionMatrix()

void tesseract_scene_graph::SceneGraph::setAllowedCollisionMatrix ( std::shared_ptr< tesseract_common::AllowedCollisionMatrix acm)

Set the allowed collision matrix.

Parameters
acmThe allowed collision matrix to assign

Definition at line 772 of file graph.cpp.

◆ 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

Definition at line 446 of file graph.cpp.

◆ 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

Definition at line 432 of file graph.cpp.

◆ setName()

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

Sets the graph name.

Parameters
nameThe name of the graph

Definition at line 246 of file graph.cpp.

◆ 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

Definition at line 256 of file graph.cpp.

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Definition at line 608 of file graph.h.

◆ tesseract_common::Serialization

friend struct tesseract_common::Serialization
friend

Definition at line 609 of file graph.h.

Member Data Documentation

◆ acm_

std::shared_ptr<tesseract_common::AllowedCollisionMatrix> tesseract_scene_graph::SceneGraph::acm_
private

Definition at line 593 of file graph.h.

◆ joint_map_

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

Definition at line 592 of file graph.h.

◆ link_map_

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

Definition at line 591 of file graph.h.


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


tesseract_scene_graph
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:49