|  | Tesseract
    Motion Planning Environment | 
#include <state_solver.h>

| 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 | |
| StateSolver & | operator= (const StateSolver &)=default | 
| StateSolver (StateSolver &&)=default | |
| StateSolver & | operator= (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... | |
| using tesseract_scene_graph::StateSolver::ConstPtr = std::shared_ptr<const StateSolver> | 
| using tesseract_scene_graph::StateSolver::ConstUPtr = std::unique_ptr<const StateSolver> | 
| using tesseract_scene_graph::StateSolver::Ptr = std::shared_ptr<StateSolver> | 
| using tesseract_scene_graph::StateSolver::UPtr = std::unique_ptr<StateSolver> | 
| 
 | default | 
| 
 | virtualdefault | 
| 
 | default | 
| 
 | default | 
| 
 | pure virtual | 
This should clone the object so it may be used in a multi threaded application where each thread would clone the solver.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the vector of joint names which align with the limits.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the vector of active link names.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the base link name.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | 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
| joint_values | The joint values | 
| link_name | The link name to calculate the jacobian | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the jacobian of the scene for a given set or subset of joint values.
This does not change the internal state of the solver.
| joints | A map of joint names to joint values to change. | 
| link_name | The link name to calculate the jacobian | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the vector of joint names.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Getter for kinematic limits.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the vector of link names.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the transform corresponding to the link.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get all of the links transforms.
Order should be the same as getLinkNames()
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the random state of the environment.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get transform between two links using the current state.
| from_link_name | The link name the transform should be relative to | 
| to_link_name | The link name to get transform | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get the current state of the scene.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | 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
| joint_values | The joint values | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | 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.
| joints | A map of joint names to joint values to change. | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Get a vector of static link names in the environment.
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Check if link name exists.
| link_name | The link name to check for | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | pure virtual | 
Check if link is an active link.
| link_name | The link name to check | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | default | 
| 
 | default | 
| 
 | pure virtual | 
Set the current state of the solver.
This must be the same size and order as what is returned by getJointNames
| joint_values | The joint values | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.
| 
 | 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.
| 
 | pure virtual | 
Implemented in tesseract_scene_graph::KDLStateSolver, and tesseract_scene_graph::OFKTStateSolver.