Go to the documentation of this file.
26 #ifndef TESSERACT_STATE_SOLVER_STATE_SOLVER_H
27 #define TESSERACT_STATE_SOLVER_STATE_SOLVER_H
34 #include <unordered_map>
35 #include <Eigen/Geometry>
48 using Ptr = std::shared_ptr<StateSolver>;
49 using ConstPtr = std::shared_ptr<const StateSolver>;
50 using UPtr = std::unique_ptr<StateSolver>;
51 using ConstUPtr = std::unique_ptr<const StateSolver>;
72 virtual void setState(
const Eigen::Ref<const Eigen::VectorXd>& joint_values,
82 virtual void setState(
const std::unordered_map<std::string, double>& joint_values,
84 virtual void setState(
const std::vector<std::string>& joint_names,
85 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
100 virtual SceneState
getState(
const Eigen::Ref<const Eigen::VectorXd>& joint_values,
112 virtual SceneState
getState(
const std::unordered_map<std::string, double>& joint_values,
114 virtual SceneState
getState(
const std::vector<std::string>& joint_names,
115 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
128 virtual SceneState
getState()
const = 0;
136 virtual Eigen::MatrixXd
getJacobian(
const Eigen::Ref<const Eigen::VectorXd>& joint_values,
137 const std::string& link_name,
152 virtual Eigen::MatrixXd
getJacobian(
const std::unordered_map<std::string, double>& joint_values,
153 const std::string& link_name,
155 virtual Eigen::MatrixXd
getJacobian(
const std::vector<std::string>& joint_names,
156 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
157 const std::string& link_name,
194 virtual std::vector<std::string>
getLinkNames()
const = 0;
220 virtual bool hasLinkName(
const std::string& link_name)
const = 0;
233 virtual Eigen::Isometry3d
getLinkTransform(
const std::string& link_name)
const = 0;
242 const std::string& to_link_name)
const = 0;
252 #endif // TESSERACT_STATE_SOLVER_STATE_SOLVER_H
StateSolver & operator=(const StateSolver &)=default
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
virtual StateSolver::UPtr clone() const =0
This should clone the object so it may be used in a multi threaded application where each thread woul...
virtual std::vector< std::string > getJointNames() const =0
Get the vector of joint names.
std::unique_ptr< const StateSolver > ConstUPtr
virtual std::vector< std::string > getActiveJointNames() const =0
Get the vector of joint names which align with the limits.
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.
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
virtual bool hasLinkName(const std::string &link_name) const =0
Check if link name exists.
virtual std::string getBaseLinkName() const =0
Get the base link name.
virtual std::vector< std::string > getFloatingJointNames() const =0
Get the vector of floating joint names.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
std::shared_ptr< const StateSolver > ConstPtr
virtual SceneState getState() const =0
Get the current state of the scene.
virtual Eigen::Isometry3d getLinkTransform(const std::string &link_name) const =0
Get the transform corresponding to the link.
virtual SceneState getRandomState() const =0
Get the random state of the environment.
virtual tesseract_common::KinematicLimits getLimits() const =0
Getter for kinematic limits.
virtual tesseract_common::VectorIsometry3d getLinkTransforms() const =0
Get all of the links transforms.
virtual bool isActiveLinkName(const std::string &link_name) const =0
Check if link is an active link.
virtual std::vector< std::string > getStaticLinkNames() const =0
Get a vector of static link names in the environment.
virtual ~StateSolver()=default
std::unique_ptr< StateSolver > UPtr
virtual std::vector< std::string > getLinkNames() const =0
Get the vector of link names.
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
std::shared_ptr< StateSolver > Ptr
virtual std::vector< std::string > getActiveLinkNames() const =0
Get the vector of active link names.
virtual void setState(const Eigen::Ref< const Eigen::VectorXd > &joint_values, const tesseract_common::TransformMap &floating_joint_values={})=0
Set the current state of the solver.
virtual Eigen::MatrixXd getJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name, const tesseract_common::TransformMap &floating_joint_values={}) const =0
Get the jacobian of the solver given the joint values.