Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
tesseract_scene_graph::StateSolver Class Referenceabstract

#include <state_solver.h>

Inheritance diagram for tesseract_scene_graph::StateSolver:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< StateSolver >
 
using ConstPtr = std::shared_ptr< const StateSolver >
 
using UPtr = std::unique_ptr< StateSolver >
 
using ConstUPtr = std::unique_ptr< const StateSolver >
 

Public Member Functions

 StateSolver ()=default
 
virtual ~StateSolver ()=default
 
 StateSolver (const StateSolver &)=default
 
StateSolveroperator= (const StateSolver &)=default
 
 StateSolver (StateSolver &&)=default
 
StateSolveroperator= (StateSolver &&)=default
 
virtual StateSolver::UPtr clone () const =0
 This should clone the object so it may be used in a multi threaded application where each thread would clone the solver. More...
 
virtual void setState (const Eigen::Ref< const Eigen::VectorXd > &joint_values)=0
 Set the current state of the solver. More...
 
virtual void setState (const std::unordered_map< std::string, double > &joint_values)=0
 Set the current state of the solver. More...
 
virtual void setState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values)=0
 
virtual SceneState getState (const Eigen::Ref< const Eigen::VectorXd > &joint_values) const =0
 Get the state of the solver given the joint values. More...
 
virtual SceneState getState (const std::unordered_map< std::string, double > &joint_values) const =0
 Get the state of the scene for a given set or subset of joint values. More...
 
virtual SceneState getState (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values) const =0
 
virtual SceneState getState () const =0
 Get the current state of the scene. More...
 
virtual Eigen::MatrixXd getJacobian (const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name) const =0
 Get the jacobian of the solver given the joint values. More...
 
virtual Eigen::MatrixXd getJacobian (const std::unordered_map< std::string, double > &joint_values, const std::string &link_name) const =0
 Get the jacobian of the scene for a given set or subset of joint values. More...
 
virtual Eigen::MatrixXd getJacobian (const std::vector< std::string > &joint_names, const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name) const =0
 
virtual SceneState getRandomState () const =0
 Get the random state of the environment. More...
 
virtual std::vector< std::string > getJointNames () const =0
 Get the vector of joint names. More...
 
virtual std::vector< std::string > getActiveJointNames () const =0
 Get the vector of joint names which align with the limits. More...
 
virtual std::string getBaseLinkName () const =0
 Get the base link name. More...
 
virtual std::vector< std::string > getLinkNames () const =0
 Get the vector of link names. More...
 
virtual std::vector< std::string > getActiveLinkNames () const =0
 Get the vector of active link names. More...
 
virtual std::vector< std::string > getStaticLinkNames () const =0
 Get a vector of static link names in the environment. More...
 
virtual bool isActiveLinkName (const std::string &link_name) const =0
 Check if link is an active link. More...
 
virtual bool hasLinkName (const std::string &link_name) const =0
 Check if link name exists. More...
 
virtual tesseract_common::VectorIsometry3d getLinkTransforms () const =0
 Get all of the links transforms. More...
 
virtual Eigen::Isometry3d getLinkTransform (const std::string &link_name) const =0
 Get the transform corresponding to the link. More...
 
virtual Eigen::Isometry3d getRelativeLinkTransform (const std::string &from_link_name, const std::string &to_link_name) const =0
 Get transform between two links using the current state. More...
 
virtual tesseract_common::KinematicLimits getLimits () const =0
 Getter for kinematic limits. More...
 

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ StateSolver() [1/3]

tesseract_scene_graph::StateSolver::StateSolver ( )
default

◆ ~StateSolver()

virtual tesseract_scene_graph::StateSolver::~StateSolver ( )
virtualdefault

◆ StateSolver() [2/3]

tesseract_scene_graph::StateSolver::StateSolver ( const StateSolver )
default

◆ StateSolver() [3/3]

tesseract_scene_graph::StateSolver::StateSolver ( StateSolver &&  )
default

Member Function Documentation

◆ clone()

virtual StateSolver::UPtr tesseract_scene_graph::StateSolver::clone ( ) const
pure virtual

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

Returns
A clone of the object.

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getActiveJointNames()

virtual std::vector< std::string > tesseract_scene_graph::StateSolver::getActiveJointNames ( ) const
pure virtual

Get the vector of joint names which align with the limits.

Returns
A vector of joint names

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getActiveLinkNames()

virtual std::vector< std::string > tesseract_scene_graph::StateSolver::getActiveLinkNames ( ) const
pure virtual

Get the vector of active link names.

Returns
A vector of active link names

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getBaseLinkName()

virtual std::string tesseract_scene_graph::StateSolver::getBaseLinkName ( ) const
pure virtual

Get the base link name.

Returns
The base link name

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getJacobian() [1/3]

virtual Eigen::MatrixXd tesseract_scene_graph::StateSolver::getJacobian ( const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const std::string &  link_name 
) const
pure virtual

Get the jacobian of the solver given the joint values.

This must be the same size and order as what is returned by getJointNames

Parameters
joint_valuesThe joint values
link_nameThe link name to calculate the jacobian

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getJacobian() [2/3]

virtual Eigen::MatrixXd tesseract_scene_graph::StateSolver::getJacobian ( const std::unordered_map< std::string, double > &  joint_values,
const std::string &  link_name 
) const
pure virtual

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

  • This does not return the jacobian based on the provided joint names. It is order based on the order returned from getJointNames

This does not change the internal state of the solver.

Parameters
jointsA map of joint names to joint values to change.
link_nameThe link name to calculate the jacobian
Returns
A the state of the environment

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getJacobian() [3/3]

virtual Eigen::MatrixXd tesseract_scene_graph::StateSolver::getJacobian ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values,
const std::string &  link_name 
) const
pure virtual

◆ getJointNames()

virtual std::vector< std::string > tesseract_scene_graph::StateSolver::getJointNames ( ) const
pure virtual

Get the vector of joint names.

Returns
A vector of joint names

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getLimits()

virtual tesseract_common::KinematicLimits tesseract_scene_graph::StateSolver::getLimits ( ) const
pure virtual

Getter for kinematic limits.

Returns
The kinematic limits

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getLinkNames()

virtual std::vector< std::string > tesseract_scene_graph::StateSolver::getLinkNames ( ) const
pure virtual

Get the vector of link names.

Returns
A vector of link names

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getLinkTransform()

virtual Eigen::Isometry3d tesseract_scene_graph::StateSolver::getLinkTransform ( const std::string &  link_name) const
pure virtual

Get the transform corresponding to the link.

Returns
Transform and is identity when no transform is available.

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getLinkTransforms()

virtual tesseract_common::VectorIsometry3d tesseract_scene_graph::StateSolver::getLinkTransforms ( ) const
pure virtual

Get all of the links transforms.

Order should be the same as getLinkNames()

Returns
Get a vector of transforms for all links.

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getRandomState()

virtual SceneState tesseract_scene_graph::StateSolver::getRandomState ( ) const
pure virtual

Get the random state of the environment.

Returns
Environment state

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getRelativeLinkTransform()

virtual Eigen::Isometry3d tesseract_scene_graph::StateSolver::getRelativeLinkTransform ( const std::string &  from_link_name,
const std::string &  to_link_name 
) const
pure virtual

Get transform between two links using the current state.

Parameters
from_link_nameThe link name the transform should be relative to
to_link_nameThe link name to get transform
Returns
The relative transform = inv(Transform(from_link_name)) * Transform(to_link_name)

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getState() [1/4]

virtual SceneState tesseract_scene_graph::StateSolver::getState ( ) const
pure virtual

Get the current state of the scene.

Returns
The current state

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getState() [2/4]

virtual SceneState tesseract_scene_graph::StateSolver::getState ( const Eigen::Ref< const Eigen::VectorXd > &  joint_values) const
pure virtual

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_valuesThe joint values

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getState() [3/4]

virtual SceneState tesseract_scene_graph::StateSolver::getState ( const std::unordered_map< std::string, double > &  joint_values) const
pure virtual

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
jointsA map of joint names to joint values to change.
Returns
A the state of the environment

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ getState() [4/4]

virtual SceneState tesseract_scene_graph::StateSolver::getState ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values 
) const
pure virtual

◆ getStaticLinkNames()

virtual std::vector< std::string > tesseract_scene_graph::StateSolver::getStaticLinkNames ( ) const
pure virtual

Get a vector of static link names in the environment.

Returns
A vector of static link names

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ hasLinkName()

virtual bool tesseract_scene_graph::StateSolver::hasLinkName ( const std::string &  link_name) const
pure virtual

Check if link name exists.

Parameters
link_nameThe link name to check for
Returns
True if it exists, otherwise false

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ isActiveLinkName()

virtual bool tesseract_scene_graph::StateSolver::isActiveLinkName ( const std::string &  link_name) const
pure virtual

Check if link is an active link.

Parameters
link_nameThe link name to check
Returns
True if active, otherwise false

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ operator=() [1/2]

StateSolver & tesseract_scene_graph::StateSolver::operator= ( const StateSolver )
default

◆ operator=() [2/2]

StateSolver & tesseract_scene_graph::StateSolver::operator= ( StateSolver &&  )
default

◆ setState() [1/3]

virtual void tesseract_scene_graph::StateSolver::setState ( const Eigen::Ref< const Eigen::VectorXd > &  joint_values)
pure virtual

Set the current state of the solver.

This must be the same size and order as what is returned by getJointNames

Parameters
joint_valuesThe joint values

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ setState() [2/3]

virtual void tesseract_scene_graph::StateSolver::setState ( const std::unordered_map< std::string, double > &  joint_values)
pure virtual

Set the current state of the solver.

After updating the current state these function must call currentStateChanged() which will update the contact managers transforms

Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.

◆ setState() [3/3]

virtual void tesseract_scene_graph::StateSolver::setState ( const std::vector< std::string > &  joint_names,
const Eigen::Ref< const Eigen::VectorXd > &  joint_values 
)
pure virtual

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