tesseract_robotics.tesseract_state_solver

The StateSolver is used to solve the transforms within the environment given a set of joints and joint positions. It is loaded from a plugin.

Classes

KDLStateSolver Class

class tesseract_robotics.tesseract_state_solver.KDLStateSolver(*args)
clone()

This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.

Return type:

UPtr

Returns:

A clone of the object.

getActiveJointNames()

Get the vector of joint names which align with the limits

Return type:

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

Returns:

A vector of joint names

getActiveLinkNames()

Get the vector of active link names

Return type:

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

Returns:

A vector of active link names

getBaseLinkName()

Get the base link name

Return type:

string

Returns:

The base link name

getJointNames()

Get the vector of joint names

Return type:

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

Returns:

A vector of joint names

getLimits()

Getter for kinematic limits

Return type:

KinematicLimits

Returns:

The kinematic limits

getLinkNames()

Get the vector of link names

Return type:

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

Returns:

A vector of link names

getLinkTransform(link_name)

Get the transform corresponding to the link.

Return type:

Isometry3d

Returns:

Transform and is identity when no transform is available.

getLinkTransforms()

Get all of the links transforms Order should be the same as getLinkNames()

Return type:

VectorIsometry3d

Returns:

Get a vector of transforms for all links.

getRandomState()

Get the random state of the environment

Return type:

SceneState

Returns:

Environment state

getRelativeLinkTransform(from_link_name, to_link_name)

Get transform between two links using the current state

Parameters:
  • from_link_name (string) – The link name the transform should be relative to

  • to_link_name (string) – The link name to get transform

Return type:

Isometry3d

Returns:

The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

getState(*args)

Overload 1:

Get the state of the solver given the joint values This must be the same size and order as what is returned by getJointNames

Parameters:

joint_values (Eigen::Ref< Eigen::VectorXd const >) – The joint values


Overload 2:

Get the state of the scene for a given set or subset of joint values.

This does not change the internal state of the solver.

Parameters:

joints – A map of joint names to joint values to change.

Return type:

SceneState

Returns:

A the state of the environment


Overload 3:

Get the current state of the scene :rtype: SceneState :return: The current state

getStaticLinkNames()

Get a vector of static link names in the environment

Return type:

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

Returns:

A vector of static link names

hasLinkName(link_name)

Check if link name exists

Parameters:

link_name (string) – The link name to check for

Return type:

boolean

Returns:

True if it exists, otherwise false

isActiveLinkName(link_name)

Check if link is an active link

Parameters:

link_name (string) – The link name to check

Return type:

boolean

Returns:

True if active, otherwise false

MutableStateSolver Class

class tesseract_robotics.tesseract_state_solver.MutableStateSolver(*args, **kwargs)

A mutable state solver allows you to reconfigure the solver’s links and joints

addLink(link, joint)

Adds a link/joint to the solver

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:

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:

getRevision()

Get the state solver revision number

Return type:

int

Returns:

revision number

insertSceneGraph(*args)

Merge a scene into the current solver

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

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

  • prefix (string, optional) – string Will be prepended to every link and joint of the merged scene

Return type:

boolean

Returns:

Return False if any link or joint name collides with current solver, otherwise True The prefix argument is meant to allow adding multiple copies of the same subgraph with different names

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 a link

Parameters:

joint (Joint) – The associated joint that defines the move

Return type:

boolean

Returns:

Return False if link does not exist or if joint name already exists, otherwise true

removeJoint(name)

Removes a joint from the graph

Parameters:

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

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

removeLink(name)

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

Return type:

boolean

Returns:

Return False if a link does not exists, otherwise true

replaceJoint(joint)

Replace and existing joint with the provided one

Parameters:

joint (Joint) – The replacement joint

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

setRevision(revision)

Set the state solver revision number

Parameters:

revision (int) – The revision number to assign

MutableStateSolverUPtr Class

class tesseract_robotics.tesseract_state_solver.MutableStateSolverUPtr(*args)
addLink(link, joint)

Adds a link/joint to the solver

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:

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:

clone()

This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.

Return type:

UPtr

Returns:

A clone of the object.

getActiveJointNames()

Get the vector of joint names which align with the limits

Return type:

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

Returns:

A vector of joint names

getActiveLinkNames()

Get the vector of active link names

Return type:

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

Returns:

A vector of active link names

getBaseLinkName()

Get the base link name

Return type:

string

Returns:

The base link name

getJointNames()

Get the vector of joint names

Return type:

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

Returns:

A vector of joint names

getLimits()

Getter for kinematic limits

Return type:

KinematicLimits

Returns:

The kinematic limits

getLinkNames()

Get the vector of link names

Return type:

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

Returns:

A vector of link names

getLinkTransform(link_name)

Get the transform corresponding to the link.

Return type:

Isometry3d

Returns:

Transform and is identity when no transform is available.

getLinkTransforms()

Get all of the links transforms Order should be the same as getLinkNames()

Return type:

VectorIsometry3d

Returns:

Get a vector of transforms for all links.

getRandomState()

Get the random state of the environment

Return type:

SceneState

Returns:

Environment state

getRelativeLinkTransform(from_link_name, to_link_name)

Get transform between two links using the current state

Parameters:
  • from_link_name (string) – The link name the transform should be relative to

  • to_link_name (string) – The link name to get transform

Return type:

Isometry3d

Returns:

The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

getRevision()

Get the state solver revision number

Return type:

int

Returns:

revision number

getState(*args)

Overload 1:

Get the state of the solver given the joint values This must be the same size and order as what is returned by getJointNames

Parameters:

joint_values (Eigen::Ref< Eigen::VectorXd const >) – The joint values


Overload 2:

Get the state of the scene for a given set or subset of joint values.

This does not change the internal state of the solver.

Parameters:

joints – A map of joint names to joint values to change.

Return type:

SceneState

Returns:

A the state of the environment


Overload 3:

Get the current state of the scene :rtype: SceneState :return: The current state

getStaticLinkNames()

Get a vector of static link names in the environment

Return type:

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

Returns:

A vector of static link names

hasLinkName(link_name)

Check if link name exists

Parameters:

link_name (string) – The link name to check for

Return type:

boolean

Returns:

True if it exists, otherwise false

insertSceneGraph(*args)

Merge a scene into the current solver

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

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

  • prefix (string, optional) – string Will be prepended to every link and joint of the merged scene

Return type:

boolean

Returns:

Return False if any link or joint name collides with current solver, otherwise True The prefix argument is meant to allow adding multiple copies of the same subgraph with different names

isActiveLinkName(link_name)

Check if link is an active link

Parameters:

link_name (string) – The link name to check

Return type:

boolean

Returns:

True if active, 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 a link

Parameters:

joint (Joint) – The associated joint that defines the move

Return type:

boolean

Returns:

Return False if link does not exist or if joint name already exists, otherwise true

removeJoint(name)

Removes a joint from the graph

Parameters:

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

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

removeLink(name)

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

Return type:

boolean

Returns:

Return False if a link does not exists, otherwise true

replaceJoint(joint)

Replace and existing joint with the provided one

Parameters:

joint (Joint) – The replacement joint

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

setRevision(revision)

Set the state solver revision number

Parameters:

revision (int) – The revision number to assign

OFKTStateSolver Class

class tesseract_robotics.tesseract_state_solver.OFKTStateSolver(*args)

An implementation of the Optimized Forward Kinematic Tree as a stat solver

Starke, S., Hendrich, N., & Zhang, J. (2018). A Forward Kinematics Data Structure for Efficient Evolutionary Inverse Kinematics. In Computational Kinematics (pp. 560-568). Springer, Cham.

addLink(link, joint)

Adds a link/joint to the solver

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:

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:

clone()

This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.

Return type:

UPtr

Returns:

A clone of the object.

getActiveJointNames()

Get the vector of joint names which align with the limits

Return type:

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

Returns:

A vector of joint names

getActiveLinkNames()

Get the vector of active link names

Return type:

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

Returns:

A vector of active link names

getBaseLinkName()

Get the base link name

Return type:

string

Returns:

The base link name

getJointNames()

Get the vector of joint names

Return type:

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

Returns:

A vector of joint names

getLimits()

Getter for kinematic limits

Return type:

KinematicLimits

Returns:

The kinematic limits

getLinkNames()

Get the vector of link names

Return type:

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

Returns:

A vector of link names

getLinkTransform(link_name)

Get the transform corresponding to the link.

Return type:

Isometry3d

Returns:

Transform and is identity when no transform is available.

getLinkTransforms()

Get all of the links transforms Order should be the same as getLinkNames()

Return type:

VectorIsometry3d

Returns:

Get a vector of transforms for all links.

getRandomState()

Get the random state of the environment

Return type:

SceneState

Returns:

Environment state

getRelativeLinkTransform(from_link_name, to_link_name)

Get transform between two links using the current state

Parameters:
  • from_link_name (string) – The link name the transform should be relative to

  • to_link_name (string) – The link name to get transform

Return type:

Isometry3d

Returns:

The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

getRevision()

Get the state solver revision number

Return type:

int

Returns:

revision number

getState(*args)

Overload 1:

Get the state of the solver given the joint values This must be the same size and order as what is returned by getJointNames

Parameters:

joint_values (Eigen::Ref< Eigen::VectorXd const >) – The joint values


Overload 2:

Get the state of the scene for a given set or subset of joint values.

This does not change the internal state of the solver.

Parameters:

joints – A map of joint names to joint values to change.

Return type:

SceneState

Returns:

A the state of the environment


Overload 3:

Get the current state of the scene :rtype: SceneState :return: The current state

getStaticLinkNames()

Get a vector of static link names in the environment

Return type:

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

Returns:

A vector of static link names

hasLinkName(link_name)

Check if link name exists

Parameters:

link_name (string) – The link name to check for

Return type:

boolean

Returns:

True if it exists, otherwise false

insertSceneGraph(*args)

Merge a scene into the current solver

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

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

  • prefix (string, optional) – string Will be prepended to every link and joint of the merged scene

Return type:

boolean

Returns:

Return False if any link or joint name collides with current solver, otherwise True The prefix argument is meant to allow adding multiple copies of the same subgraph with different names

isActiveLinkName(link_name)

Check if link is an active link

Parameters:

link_name (string) – The link name to check

Return type:

boolean

Returns:

True if active, 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 a link

Parameters:

joint (Joint) – The associated joint that defines the move

Return type:

boolean

Returns:

Return False if link does not exist or if joint name already exists, otherwise true

removeJoint(name)

Removes a joint from the graph

Parameters:

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

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

removeLink(name)

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

Return type:

boolean

Returns:

Return False if a link does not exists, otherwise true

replaceJoint(joint)

Replace and existing joint with the provided one

Parameters:

joint (Joint) – The replacement joint

Return type:

boolean

Returns:

Return False if a joint does not exists, otherwise true

setRevision(revision)

Set the state solver revision number

Parameters:

revision (int) – The revision number to assign

StateSolver Class

class tesseract_robotics.tesseract_state_solver.StateSolver(*args, **kwargs)
clone()

This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.

Return type:

UPtr

Returns:

A clone of the object.

getActiveJointNames()

Get the vector of joint names which align with the limits

Return type:

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

Returns:

A vector of joint names

getActiveLinkNames()

Get the vector of active link names

Return type:

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

Returns:

A vector of active link names

getBaseLinkName()

Get the base link name

Return type:

string

Returns:

The base link name

getJointNames()

Get the vector of joint names

Return type:

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

Returns:

A vector of joint names

getLimits()

Getter for kinematic limits

Return type:

KinematicLimits

Returns:

The kinematic limits

getLinkNames()

Get the vector of link names

Return type:

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

Returns:

A vector of link names

getLinkTransform(link_name)

Get the transform corresponding to the link.

Return type:

Isometry3d

Returns:

Transform and is identity when no transform is available.

getLinkTransforms()

Get all of the links transforms Order should be the same as getLinkNames()

Return type:

VectorIsometry3d

Returns:

Get a vector of transforms for all links.

getRandomState()

Get the random state of the environment

Return type:

SceneState

Returns:

Environment state

getRelativeLinkTransform(from_link_name, to_link_name)

Get transform between two links using the current state

Parameters:
  • from_link_name (string) – The link name the transform should be relative to

  • to_link_name (string) – The link name to get transform

Return type:

Isometry3d

Returns:

The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

getState(*args)

Overload 1:

Get the state of the solver given the joint values This must be the same size and order as what is returned by getJointNames

Parameters:

joint_values (Eigen::Ref< Eigen::VectorXd const >) – The joint values


Overload 2:

Get the state of the scene for a given set or subset of joint values.

This does not change the internal state of the solver.

Parameters:

joints – A map of joint names to joint values to change.

Return type:

SceneState

Returns:

A the state of the environment


Overload 3:

Get the current state of the scene :rtype: SceneState :return: The current state

getStaticLinkNames()

Get a vector of static link names in the environment

Return type:

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

Returns:

A vector of static link names

hasLinkName(link_name)

Check if link name exists

Parameters:

link_name (string) – The link name to check for

Return type:

boolean

Returns:

True if it exists, otherwise false

isActiveLinkName(link_name)

Check if link is an active link

Parameters:

link_name (string) – The link name to check

Return type:

boolean

Returns:

True if active, otherwise false

StateSolverUPtr Class

class tesseract_robotics.tesseract_state_solver.StateSolverUPtr(*args)
clone()

This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.

Return type:

UPtr

Returns:

A clone of the object.

getActiveJointNames()

Get the vector of joint names which align with the limits

Return type:

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

Returns:

A vector of joint names

getActiveLinkNames()

Get the vector of active link names

Return type:

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

Returns:

A vector of active link names

getBaseLinkName()

Get the base link name

Return type:

string

Returns:

The base link name

getJointNames()

Get the vector of joint names

Return type:

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

Returns:

A vector of joint names

getLimits()

Getter for kinematic limits

Return type:

KinematicLimits

Returns:

The kinematic limits

getLinkNames()

Get the vector of link names

Return type:

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

Returns:

A vector of link names

getLinkTransform(link_name)

Get the transform corresponding to the link.

Return type:

Isometry3d

Returns:

Transform and is identity when no transform is available.

getLinkTransforms()

Get all of the links transforms Order should be the same as getLinkNames()

Return type:

VectorIsometry3d

Returns:

Get a vector of transforms for all links.

getRandomState()

Get the random state of the environment

Return type:

SceneState

Returns:

Environment state

getRelativeLinkTransform(from_link_name, to_link_name)

Get transform between two links using the current state

Parameters:
  • from_link_name (string) – The link name the transform should be relative to

  • to_link_name (string) – The link name to get transform

Return type:

Isometry3d

Returns:

The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

getState(*args)

Overload 1:

Get the state of the solver given the joint values This must be the same size and order as what is returned by getJointNames

Parameters:

joint_values (Eigen::Ref< Eigen::VectorXd const >) – The joint values


Overload 2:

Get the state of the scene for a given set or subset of joint values.

This does not change the internal state of the solver.

Parameters:

joints – A map of joint names to joint values to change.

Return type:

SceneState

Returns:

A the state of the environment


Overload 3:

Get the current state of the scene :rtype: SceneState :return: The current state

getStaticLinkNames()

Get a vector of static link names in the environment

Return type:

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

Returns:

A vector of static link names

hasLinkName(link_name)

Check if link name exists

Parameters:

link_name (string) – The link name to check for

Return type:

boolean

Returns:

True if it exists, otherwise false

isActiveLinkName(link_name)

Check if link is an active link

Parameters:

link_name (string) – The link name to check

Return type:

boolean

Returns:

True if active, otherwise false