tesseract_robotics.tesseract_scene_graph

The tesseract_scene_graph package manages the scene graph for the Tesseract environment. The user will typically only use classes in This module if modifying the environment after it has been loaded from a URDF.

Classes

Collision Class

class tesseract_robotics.tesseract_scene_graph.Collision

Inertial Class

class tesseract_robotics.tesseract_scene_graph.Inertial

Joint Class

class tesseract_robotics.tesseract_scene_graph.Joint(*args)
property axis

type_ meaning of axis_

UNKNOWN unknown type REVOLUTE rotation axis PRISMATIC translation axis FLOATING N/A PLANAR plane normal axis FIXED N/A

property calibration

Unsupported Hidden Feature

property child_link_name
child Link element

child link frame is the same as the Joint frame

property dynamics

Joint Dynamics

property limits

Joint Limits

property mimic

Option to Mimic another Joint

property parent_link_name
parent Link element

origin specifies the transform from Parent Link to Joint Frame

property parent_to_joint_origin_transform

transform from Parent Link frame to Joint frame

property safety

Unsupported Hidden Feature

property type

The type of joint

JointCalibration Class

class tesseract_robotics.tesseract_scene_graph.JointCalibration(*args)

JointDynamics Class

class tesseract_robotics.tesseract_scene_graph.JointDynamics(*args)

JointLimits Class

class tesseract_robotics.tesseract_scene_graph.JointLimits(*args)

JointMimic Class

class tesseract_robotics.tesseract_scene_graph.JointMimic(*args)

JointSafety Class

class tesseract_robotics.tesseract_scene_graph.JointSafety(*args)

Parameters for Joint Safety Controllers

property soft_upper_limit

IMPORTANT: The safety controller support is very much PR2 specific, not intended for generic usage.

Basic safety controller operation is as follows

current safety controllers will take effect on joints outside the position range below:

position range: [JointSafety::soft_lower_limit + JointLimits::velocity / JointSafety::k_position,

JointSafety::soft_uppper_limit - JointLimits::velocity / JointSafety::k_position]

if (joint_position is outside of the position range above)

velocity_limit_min = -JointLimits::velocity + JointSafety::k_position * (joint_position - JointSafety::soft_lower_limit) velocity_limit_max = JointLimits::velocity + JointSafety::k_position * (joint_position - JointSafety::soft_upper_limit)

else

velocity_limit_min = -JointLimits::velocity velocity_limit_max = JointLimits::velocity

velocity range: [velocity_limit_min + JointLimits::effort / JointSafety::k_velocity,

velocity_limit_max - JointLimits::effort / JointSafety::k_velocity]

if (joint_velocity is outside of the velocity range above)

effort_limit_min = -JointLimits::effort + JointSafety::k_velocity * (joint_velocity - velocity_limit_min) effort_limit_max = JointLimits::effort + JointSafety::k_velocity * (joint_velocity - velocity_limit_max)

else

effort_limit_min = -JointLimits::effort effort_limit_max = JointLimits::effort

Final effort command sent to the joint is saturated by [effort_limit_min,effort_limit_max]

Please see wiki for more details: http://www.ros.org/wiki/pr2_controller_manager/safety_limits

Material Class

class tesseract_robotics.tesseract_scene_graph.Material(*args)

SceneGraph Class

class tesseract_robotics.tesseract_scene_graph.SceneGraph(*args)
addAllowedCollision(link_name1, link_name2, reason)

Disable collision between two collision objects

Parameters:
  • link_name1 (string) – Collision object name

  • link_name2 (string) – Collision object name

  • reason (string) – The reason for disabling collision

addJoint(joint)

Adds joint to the graph

Parameters:

joint (Joint) – The joint to be added

Return type:

boolean

Returns:

Return False if parent or child link does not exists and if joint name already exists in the graph, otherwise true

addLink(*args)

Overload 1:

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 (Link) – The link to be added to the graph

  • replace_allowed (boolean, optional) – If true and the link exist it will be replaced

Return type:

boolean

Returns:

Return False if a link with the same name already exists and replace is not allowed, otherwise true


Overload 2:

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:
  • link (Link) – The link to be added to the graph

  • joint (Joint) – The associated joint to be added to the graph

Return type:

boolean

Returns:

Return False if a link with the same name allready exists, otherwise true

changeJointAccelerationLimits(name, limit)

Changes the acceleration limits associated with a joint

Parameters:
  • joint_name – Name of the joint to be updated

  • limits – New acceleration limits to be set as the joint limits

Return type:

boolean

Returns:

changeJointLimits(name, limits)

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

Parameters:
  • name (string) – Name of the joint to be changed

  • limits (JointLimits) – The new limits associated with the joint

Return type:

boolean

Returns:

True if successful.

changeJointOrigin(name, new_origin)

Changes the “origin” transform of the joint and recomputes the associated edge

Parameters:
  • name (string) – Name of the joint to be changed

  • new_origin (Isometry3d) – The new transform associated with the joint

Return type:

boolean

Returns:

True if successful.

changeJointPositionLimits(name, lower, upper)

Changes the position limits associated with a joint

Parameters:
  • joint_name – Name of the joint to be updated

  • limits – New position limits to be set as the joint limits if successful.

changeJointVelocityLimits(name, limit)

Changes the velocity limits associated with a joint

Parameters:
  • joint_name – Name of the joint to be updated

  • limits – New velocity limits to be set as the joint limits

Return type:

boolean

Returns:

clear()

Clear the scene graph

clearAllowedCollisions()

Remove all allowed collisions

clone()

Clone the scene graph

Return type:

UPtr

Returns:

The cloned scene graph

getActiveJoints()

Get a vector of active joints in the scene graph

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

A vector of active joints

getAdjacencyMap(link_names)

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

Parameters:

link_names (std::vector< std::string,std::allocator< std::string > >) – The links to map other links to

Return type:

std::unordered_map< std::string,std::string,std::hash< std::string >,std::equal_to< std::string >,std::allocator< std::pair< std::string const,std::string > > >

Returns:

A map of affected links to on of the provided link names.

getAdjacentLinkNames(name)

Get a vector of adjacent link names provided a link name

Parameters:

name (string) – Name of link

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of adjacent link names

getAllowedCollisionMatrix(*args)

Overload 1:

Get the allowed collision matrix

Return type:

AllowedCollisionMatrix

Returns:

AllowedCollisionMatrixConstPtr


Overload 2:

Get the allowed collision matrix

Return type:

AllowedCollisionMatrix

Returns:

AllowedCollisionMatrixPtr

getInboundJoints(link_name)

Get inbound joints for a link

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

Parameters:

link_name (string) – The name of the link

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

Vector of joints

getInvAdjacentLinkNames(name)

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

Parameters:

name (string) –

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

getJoint(name)

Get a joint in the graph

Parameters:

name (string) – The name of the joint

Return type:

Joint

Returns:

Return nullptr if joint name does not exists, otherwise a pointer to the joint

getJointChildrenNames(*args)

Overload 1:

Get all children link names for a given joint name

Parameters:

name (string) – Name of joint

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of child link names


Overload 2:

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:

names (std::vector< std::string,std::allocator< std::string > >) – Name of joints

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of child link names

getJointLimits(name)

Gets the limits of the joint specified by name

Parameters:

name (string) – Name of the joint which limits will be retrieved

Return type:

JointLimits

Returns:

Limits of the joint. Returns nullptr is joint is not found.

getJoints()

Get a vector of joints in the scene graph

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

A vector of joints

getLeafLinks()

Get a vector leaf links in the scene graph

Return type:

std::vector< tesseract_scene_graph::Link::ConstPtr,std::allocator< tesseract_scene_graph::Link::ConstPtr > >

Returns:

A vector of links

getLink(name)

Get a link in the graph

Parameters:

name (string) – The name of the link

Return type:

Link

Returns:

Return nullptr if link name does not exists, otherwise a pointer to the link

getLinkChildrenNames(name)

Get all children for a given link name

Parameters:

name (string) – Name of Link

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of child link names

getLinkCollisionEnabled(name)

Get whether a link should be considered during collision checking

Return type:

boolean

Returns:

True if should be considered during collision checking, otherwise false

getLinkVisibility(name)

Get a given links visibility setting

Return type:

boolean

Returns:

True if should be visible, otherwise false

getLinks()

Get a vector links in the scene graph

Return type:

std::vector< tesseract_scene_graph::Link::ConstPtr,std::allocator< tesseract_scene_graph::Link::ConstPtr > >

Returns:

A vector of links

getName()

Sets the graph name

Parameters:

name – The name of the graph

getOutboundJoints(link_name)

Get outbound joints for a link

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

Parameters:

link_name (string) – The name of the link

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

Vector of joints

getRoot()

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

Return type:

string

Returns:

The root link name

getShortestPath(root, tip)

Get the shortest path between two links

Parameters:
  • root (string) – The base link

  • tip (string) – The tip link

Return type:

ShortestPath

Returns:

The shortest path between the two links

getSourceLink(joint_name)

Get the source link (parent link) for a joint

Parameters:

joint_name (string) – The name of the joint

Return type:

Link

Returns:

The source link

getTargetLink(joint_name)

Get the target link (child link) for a joint

Parameters:

joint_name (string) – The name of the joint

Return type:

Link

Returns:

The target link

insertSceneGraph(*args)

Overload 1:

Merge a graph into the current graph

Parameters:
  • scene_graph (SceneGraph) – Const ref to the graph to be merged (said graph will be copied)

  • prefix (string, optional) – string Will prepend to every link and joint of the merged graph

Return type:

boolean

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


Overload 2:

Merge a graph into the current environment

Parameters:
  • scene_graph (SceneGraph) – Const ref to the graph to be merged (said graph will be copied)

  • joint (Joint) – The joint that connects current environment with the inserted graph

  • prefix (string, optional) – string Will prepend to every link and joint of the merged graph

Return type:

boolean

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


Overload 3:

Merge a graph into the current environment :type scene_graph: SceneGraph :param scene_graph: Const ref to the graph to be merged (said graph will be copied) :type joint: Joint :param joint: The joint that connects current environment with the inserted graph :param prefix: string Will prepend to every link and joint of the merged graph :rtype: boolean :return: 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()

Determine if the graph contains cycles

Return type:

boolean

Returns:

True if graph is acyclic (no cycles) otherwise false

isCollisionAllowed(link_name1, link_name2)

Check if two links are allowed to be in collision

Parameters:
  • link_name1 (string) – link name

  • link_name2 (string) – link name

Return type:

boolean

Returns:

True if the two links are allowed to be in collision, otherwise false

isEmpty()

Check if the graph is empty

Return type:

boolean

Returns:

True if empty, otherwise false

isTree()

Determine if the graph is a tree

Return type:

boolean

Returns:

True if graph is tree otherwise false

moveJoint(name, parent_link)

Move joint to new parent link

Parameters:
  • name (string) – Name of the joint to move

  • parent_link (string) – Name of parent link to move to

Return type:

boolean

Returns:

Returns true if successful, otherwise false.

moveLink(joint)

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

Parameters:

joint (Joint) – The joint defining the link move

Return type:

boolean

Returns:

Returns true if successful, otherwise false.

removeAllowedCollision(*args)

Overload 1:

Remove disabled collision pair from allowed collision matrix

Parameters:
  • link_name1 (string) – Collision object name

  • link_name2 (string) – Collision object name


Overload 2:

Remove disabled collision for any pair with link_name from allowed collision matrix :type link_name: string :param link_name: Collision object name

removeJoint(name, recursive=False)

Removes a joint from the graph

Parameters:
  • name (string) – Name of the joint to be removed

  • recursive (boolean, optional) – If true all children are removed if this this is the only joint of the child link

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

removeLink(name, recursive=False)

Removes a link from the graph

Note: this will remove all inbound and outbound edges

Parameters:
  • name (string) – Name of the link to be removed

  • recursive (boolean, optional) – If true all children are removed if it only has a single joint

Return type:

boolean

Returns:

Return False if a link does not exists, otherwise true

saveDOT(path)

Saves Graph as Graph Description Language (DOT)

Parameters:

path (string) – The file path

setLinkCollisionEnabled(name, enabled)

Set whether a link should be considered during collision checking

Parameters:

enabled (boolean) – True if should be considered during collision checking, otherwise false

setLinkVisibility(name, visibility)

Set a links visibility

Parameters:

visibility (boolean) – True if should be visible, otherwise false

setName(name)

Sets the graph name

Parameters:

name (string) – The name of the graph

setRoot(name)

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

Parameters:

name (string) – The name of the link

Return type:

boolean

Returns:

Return False if a link does not exists, otherwise true

SceneGraphUPtr Class

class tesseract_robotics.tesseract_scene_graph.SceneGraphUPtr(*args)
addAllowedCollision(link_name1, link_name2, reason)

Disable collision between two collision objects

Parameters:
  • link_name1 (string) – Collision object name

  • link_name2 (string) – Collision object name

  • reason (string) – The reason for disabling collision

addJoint(joint)

Adds joint to the graph

Parameters:

joint (Joint) – The joint to be added

Return type:

boolean

Returns:

Return False if parent or child link does not exists and if joint name already exists in the graph, otherwise true

addLink(*args)

Overload 1:

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 (Link) – The link to be added to the graph

  • replace_allowed (boolean, optional) – If true and the link exist it will be replaced

Return type:

boolean

Returns:

Return False if a link with the same name already exists and replace is not allowed, otherwise true


Overload 2:

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:
  • link (Link) – The link to be added to the graph

  • joint (Joint) – The associated joint to be added to the graph

Return type:

boolean

Returns:

Return False if a link with the same name allready exists, otherwise true

changeJointAccelerationLimits(name, limit)

Changes the acceleration limits associated with a joint

Parameters:
  • joint_name – Name of the joint to be updated

  • limits – New acceleration limits to be set as the joint limits

Return type:

boolean

Returns:

changeJointLimits(name, limits)

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

Parameters:
  • name (string) – Name of the joint to be changed

  • limits (JointLimits) – The new limits associated with the joint

Return type:

boolean

Returns:

True if successful.

changeJointOrigin(name, new_origin)

Changes the “origin” transform of the joint and recomputes the associated edge

Parameters:
  • name (string) – Name of the joint to be changed

  • new_origin (Isometry3d) – The new transform associated with the joint

Return type:

boolean

Returns:

True if successful.

changeJointPositionLimits(name, lower, upper)

Changes the position limits associated with a joint

Parameters:
  • joint_name – Name of the joint to be updated

  • limits – New position limits to be set as the joint limits if successful.

changeJointVelocityLimits(name, limit)

Changes the velocity limits associated with a joint

Parameters:
  • joint_name – Name of the joint to be updated

  • limits – New velocity limits to be set as the joint limits

Return type:

boolean

Returns:

clear()

Clear the scene graph

clearAllowedCollisions()

Remove all allowed collisions

clone()

Clone the scene graph

Return type:

UPtr

Returns:

The cloned scene graph

getActiveJoints()

Get a vector of active joints in the scene graph

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

A vector of active joints

getAdjacencyMap(link_names)

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

Parameters:

link_names (std::vector< std::string,std::allocator< std::string > >) – The links to map other links to

Return type:

std::unordered_map< std::string,std::string,std::hash< std::string >,std::equal_to< std::string >,std::allocator< std::pair< std::string const,std::string > > >

Returns:

A map of affected links to on of the provided link names.

getAdjacentLinkNames(name)

Get a vector of adjacent link names provided a link name

Parameters:

name (string) – Name of link

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of adjacent link names

getAllowedCollisionMatrix(*args)

Overload 1:

Get the allowed collision matrix

Return type:

AllowedCollisionMatrix

Returns:

AllowedCollisionMatrixConstPtr


Overload 2:

Get the allowed collision matrix

Return type:

AllowedCollisionMatrix

Returns:

AllowedCollisionMatrixPtr

getInboundJoints(link_name)

Get inbound joints for a link

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

Parameters:

link_name (string) – The name of the link

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

Vector of joints

getInvAdjacentLinkNames(name)

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

Parameters:

name (string) –

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

getJoint(name)

Get a joint in the graph

Parameters:

name (string) – The name of the joint

Return type:

Joint

Returns:

Return nullptr if joint name does not exists, otherwise a pointer to the joint

getJointChildrenNames(*args)

Overload 1:

Get all children link names for a given joint name

Parameters:

name (string) – Name of joint

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of child link names


Overload 2:

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:

names (std::vector< std::string,std::allocator< std::string > >) – Name of joints

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of child link names

getJointLimits(name)

Gets the limits of the joint specified by name

Parameters:

name (string) – Name of the joint which limits will be retrieved

Return type:

JointLimits

Returns:

Limits of the joint. Returns nullptr is joint is not found.

getJoints()

Get a vector of joints in the scene graph

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

A vector of joints

getLeafLinks()

Get a vector leaf links in the scene graph

Return type:

std::vector< tesseract_scene_graph::Link::ConstPtr,std::allocator< tesseract_scene_graph::Link::ConstPtr > >

Returns:

A vector of links

getLink(name)

Get a link in the graph

Parameters:

name (string) – The name of the link

Return type:

Link

Returns:

Return nullptr if link name does not exists, otherwise a pointer to the link

getLinkChildrenNames(name)

Get all children for a given link name

Parameters:

name (string) – Name of Link

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

A vector of child link names

getLinkCollisionEnabled(name)

Get whether a link should be considered during collision checking

Return type:

boolean

Returns:

True if should be considered during collision checking, otherwise false

getLinkVisibility(name)

Get a given links visibility setting

Return type:

boolean

Returns:

True if should be visible, otherwise false

getLinks()

Get a vector links in the scene graph

Return type:

std::vector< tesseract_scene_graph::Link::ConstPtr,std::allocator< tesseract_scene_graph::Link::ConstPtr > >

Returns:

A vector of links

getName()

Sets the graph name

Parameters:

name – The name of the graph

getOutboundJoints(link_name)

Get outbound joints for a link

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

Parameters:

link_name (string) – The name of the link

Return type:

std::vector< tesseract_scene_graph::Joint::ConstPtr,std::allocator< tesseract_scene_graph::Joint::ConstPtr > >

Returns:

Vector of joints

getRoot()

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

Return type:

string

Returns:

The root link name

getShortestPath(root, tip)

Get the shortest path between two links

Parameters:
  • root (string) – The base link

  • tip (string) – The tip link

Return type:

ShortestPath

Returns:

The shortest path between the two links

getSourceLink(joint_name)

Get the source link (parent link) for a joint

Parameters:

joint_name (string) – The name of the joint

Return type:

Link

Returns:

The source link

getTargetLink(joint_name)

Get the target link (child link) for a joint

Parameters:

joint_name (string) – The name of the joint

Return type:

Link

Returns:

The target link

insertSceneGraph(*args)

Overload 1:

Merge a graph into the current graph

Parameters:
  • scene_graph (SceneGraph) – Const ref to the graph to be merged (said graph will be copied)

  • prefix (string, optional) – string Will prepend to every link and joint of the merged graph

Return type:

boolean

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


Overload 2:

Merge a graph into the current environment

Parameters:
  • scene_graph (SceneGraph) – Const ref to the graph to be merged (said graph will be copied)

  • joint (Joint) – The joint that connects current environment with the inserted graph

  • prefix (string, optional) – string Will prepend to every link and joint of the merged graph

Return type:

boolean

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


Overload 3:

Merge a graph into the current environment :type scene_graph: SceneGraph :param scene_graph: Const ref to the graph to be merged (said graph will be copied) :type joint: Joint :param joint: The joint that connects current environment with the inserted graph :param prefix: string Will prepend to every link and joint of the merged graph :rtype: boolean :return: 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()

Determine if the graph contains cycles

Return type:

boolean

Returns:

True if graph is acyclic (no cycles) otherwise false

isCollisionAllowed(link_name1, link_name2)

Check if two links are allowed to be in collision

Parameters:
  • link_name1 (string) – link name

  • link_name2 (string) – link name

Return type:

boolean

Returns:

True if the two links are allowed to be in collision, otherwise false

isEmpty()

Check if the graph is empty

Return type:

boolean

Returns:

True if empty, otherwise false

isTree()

Determine if the graph is a tree

Return type:

boolean

Returns:

True if graph is tree otherwise false

moveJoint(name, parent_link)

Move joint to new parent link

Parameters:
  • name (string) – Name of the joint to move

  • parent_link (string) – Name of parent link to move to

Return type:

boolean

Returns:

Returns true if successful, otherwise false.

moveLink(joint)

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

Parameters:

joint (Joint) – The joint defining the link move

Return type:

boolean

Returns:

Returns true if successful, otherwise false.

removeAllowedCollision(*args)

Overload 1:

Remove disabled collision pair from allowed collision matrix

Parameters:
  • link_name1 (string) – Collision object name

  • link_name2 (string) – Collision object name


Overload 2:

Remove disabled collision for any pair with link_name from allowed collision matrix :type link_name: string :param link_name: Collision object name

removeJoint(name, recursive=False)

Removes a joint from the graph

Parameters:
  • name (string) – Name of the joint to be removed

  • recursive (boolean, optional) – If true all children are removed if this this is the only joint of the child link

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

removeLink(name, recursive=False)

Removes a link from the graph

Note: this will remove all inbound and outbound edges

Parameters:
  • name (string) – Name of the link to be removed

  • recursive (boolean, optional) – If true all children are removed if it only has a single joint

Return type:

boolean

Returns:

Return False if a link does not exists, otherwise true

saveDOT(path)

Saves Graph as Graph Description Language (DOT)

Parameters:

path (string) – The file path

setLinkCollisionEnabled(name, enabled)

Set whether a link should be considered during collision checking

Parameters:

enabled (boolean) – True if should be considered during collision checking, otherwise false

setLinkVisibility(name, visibility)

Set a links visibility

Parameters:

visibility (boolean) – True if should be visible, otherwise false

setName(name)

Sets the graph name

Parameters:

name (string) – The name of the graph

setRoot(name)

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

Parameters:

name (string) – The name of the link

Return type:

boolean

Returns:

Return False if a link does not exists, otherwise true

SceneState Class

class tesseract_robotics.tesseract_scene_graph.SceneState

This holds a state of the scene

It provides a way to look up the location of a link/joint in world coordinates system by link/joint name. It is possible to get the joint transform using the child link transform of the joint, but they are both provided for convenience. Also the joint values used to calculated the link/joint transforms is provided.

property joint_transforms

The joint transforms in world coordinate system

property joints

The joint values used for calculating the joint and link transforms

property link_transforms

The link transforms in world coordinate system

ShortestPath Class

class tesseract_robotics.tesseract_scene_graph.ShortestPath

Holds the shortest path information.

property active_joints

A list of active joints along the shortest path

property joints

A list of joints along the shortest path

property links

a list of links along the shortest path

Visual Class

class tesseract_robotics.tesseract_scene_graph.Visual

Constants

  • JointType_CONTINUOUS

  • JointType_FIXED

  • JointType_FLOATING

  • JointType_PLANAR

  • JointType_PRISMATIC

  • JointType_REVOLUTE

  • JointType_UNKNOWN

Container Templates

  • JointConstVector -> std::vector<std::shared_ptr<tesseract_scene_graph::Joint const> >

  • JointVector -> std::vector<std::shared_ptr<tesseract_scene_graph::Joint> >

  • LinkConstVector -> std::vector<std::shared_ptr<tesseract_scene_graph::Link const> >

  • LinkVector -> std::vector<std::shared_ptr<tesseract_scene_graph::Link> >

  • tesseract_scene_graph_CollisionVector -> std::vector<std::shared_ptr<tesseract_scene_graph::Collision> >

  • tesseract_scene_graph_VisualVector -> std::vector<std::shared_ptr<tesseract_scene_graph::Visual> >