state_solver.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_STATE_SOLVER_STATE_SOLVER_H
27 #define TESSERACT_STATE_SOLVER_STATE_SOLVER_H
28 
31 #include <vector>
32 #include <string>
33 #include <memory>
34 #include <unordered_map>
35 #include <Eigen/Geometry>
36 #include <Eigen/Core>
38 
39 #include <tesseract_common/fwd.h>
42 
43 namespace tesseract_scene_graph
44 {
46 {
47 public:
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>;
52 
53  StateSolver() = default;
54  virtual ~StateSolver() = default;
55  StateSolver(const StateSolver&) = default;
56  StateSolver& operator=(const StateSolver&) = default;
57  StateSolver(StateSolver&&) = default;
58  StateSolver& operator=(StateSolver&&) = default;
59 
65  virtual StateSolver::UPtr clone() const = 0;
66 
72  virtual void setState(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
73  const tesseract_common::TransformMap& floating_joint_values = {}) = 0;
74 
82  virtual void setState(const std::unordered_map<std::string, double>& joint_values,
83  const tesseract_common::TransformMap& floating_joint_values = {}) = 0;
84  virtual void setState(const std::vector<std::string>& joint_names,
85  const Eigen::Ref<const Eigen::VectorXd>& joint_values,
86  const tesseract_common::TransformMap& floating_joint_values = {}) = 0;
87 
92  virtual void setState(const tesseract_common::TransformMap& floating_joint_values) = 0;
93 
100  virtual SceneState getState(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
101  const tesseract_common::TransformMap& floating_joint_values = {}) const = 0;
102 
112  virtual SceneState getState(const std::unordered_map<std::string, double>& joint_values,
113  const tesseract_common::TransformMap& floating_joint_values = {}) const = 0;
114  virtual SceneState getState(const std::vector<std::string>& joint_names,
115  const Eigen::Ref<const Eigen::VectorXd>& joint_values,
116  const tesseract_common::TransformMap& floating_joint_values = {}) const = 0;
122  virtual SceneState getState(const tesseract_common::TransformMap& floating_joint_values) const = 0;
123 
128  virtual SceneState getState() const = 0;
129 
136  virtual Eigen::MatrixXd getJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
137  const std::string& link_name,
138  const tesseract_common::TransformMap& floating_joint_values = {}) const = 0;
139 
152  virtual Eigen::MatrixXd getJacobian(const std::unordered_map<std::string, double>& joint_values,
153  const std::string& link_name,
154  const tesseract_common::TransformMap& floating_joint_values = {}) const = 0;
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,
158  const tesseract_common::TransformMap& floating_joint_values = {}) const = 0;
159 
164  virtual SceneState getRandomState() const = 0;
165 
170  virtual std::vector<std::string> getJointNames() const = 0;
171 
176  virtual std::vector<std::string> getFloatingJointNames() const = 0;
177 
182  virtual std::vector<std::string> getActiveJointNames() const = 0;
183 
188  virtual std::string getBaseLinkName() const = 0;
189 
194  virtual std::vector<std::string> getLinkNames() const = 0;
195 
200  virtual std::vector<std::string> getActiveLinkNames() const = 0;
201 
206  virtual std::vector<std::string> getStaticLinkNames() const = 0;
207 
213  virtual bool isActiveLinkName(const std::string& link_name) const = 0;
214 
220  virtual bool hasLinkName(const std::string& link_name) const = 0;
221 
228 
233  virtual Eigen::Isometry3d getLinkTransform(const std::string& link_name) const = 0;
234 
241  virtual Eigen::Isometry3d getRelativeLinkTransform(const std::string& from_link_name,
242  const std::string& to_link_name) const = 0;
243 
248  virtual tesseract_common::KinematicLimits getLimits() const = 0;
249 };
250 } // namespace tesseract_scene_graph
251 
252 #endif // TESSERACT_STATE_SOLVER_STATE_SOLVER_H
tesseract_scene_graph::StateSolver::operator=
StateSolver & operator=(const StateSolver &)=default
tesseract_common::VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_scene_graph::StateSolver::clone
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...
tesseract_scene_graph::StateSolver::getJointNames
virtual std::vector< std::string > getJointNames() const =0
Get the vector of joint names.
tesseract_scene_graph::StateSolver::ConstUPtr
std::unique_ptr< const StateSolver > ConstUPtr
Definition: state_solver.h:51
tesseract_scene_graph::StateSolver::getActiveJointNames
virtual std::vector< std::string > getActiveJointNames() const =0
Get the vector of joint names which align with the limits.
tesseract_scene_graph::StateSolver::getRelativeLinkTransform
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.
tesseract_common::KinematicLimits
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_scene_graph::StateSolver::hasLinkName
virtual bool hasLinkName(const std::string &link_name) const =0
Check if link name exists.
tesseract_scene_graph::StateSolver::getBaseLinkName
virtual std::string getBaseLinkName() const =0
Get the base link name.
tesseract_scene_graph::StateSolver::getFloatingJointNames
virtual std::vector< std::string > getFloatingJointNames() const =0
Get the vector of floating joint names.
tesseract_scene_graph::StateSolver
Definition: state_solver.h:45
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::StateSolver::ConstPtr
std::shared_ptr< const StateSolver > ConstPtr
Definition: state_solver.h:49
tesseract_scene_graph::StateSolver::StateSolver
StateSolver()=default
tesseract_scene_graph::StateSolver::getState
virtual SceneState getState() const =0
Get the current state of the scene.
tesseract_scene_graph::StateSolver::getLinkTransform
virtual Eigen::Isometry3d getLinkTransform(const std::string &link_name) const =0
Get the transform corresponding to the link.
tesseract_scene_graph::StateSolver::getRandomState
virtual SceneState getRandomState() const =0
Get the random state of the environment.
tesseract_scene_graph::StateSolver::getLimits
virtual tesseract_common::KinematicLimits getLimits() const =0
Getter for kinematic limits.
tesseract_scene_graph::StateSolver::getLinkTransforms
virtual tesseract_common::VectorIsometry3d getLinkTransforms() const =0
Get all of the links transforms.
tesseract_scene_graph::StateSolver::isActiveLinkName
virtual bool isActiveLinkName(const std::string &link_name) const =0
Check if link is an active link.
tesseract_scene_graph::StateSolver::getStaticLinkNames
virtual std::vector< std::string > getStaticLinkNames() const =0
Get a vector of static link names in the environment.
tesseract_scene_graph::StateSolver::~StateSolver
virtual ~StateSolver()=default
fwd.h
tesseract_scene_graph::StateSolver::UPtr
std::unique_ptr< StateSolver > UPtr
Definition: state_solver.h:50
tesseract_scene_graph::StateSolver::getLinkNames
virtual std::vector< std::string > getLinkNames() const =0
Get the vector of link names.
eigen_types.h
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_scene_graph::StateSolver::Ptr
std::shared_ptr< StateSolver > Ptr
Definition: state_solver.h:48
tesseract_scene_graph::StateSolver::getActiveLinkNames
virtual std::vector< std::string > getActiveLinkNames() const =0
Get the vector of active link names.
macros.h
tesseract_scene_graph
tesseract_scene_graph::StateSolver::setState
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.
tesseract_scene_graph::StateSolver::getJacobian
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.


tesseract_state_solver
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:10