mutable_state_solver.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_STATE_SOLVER_MUTABLE_STATE_SOLVER_H
27 #define TESSERACT_STATE_SOLVER_MUTABLE_STATE_SOLVER_H
28 
30 
31 namespace tesseract_scene_graph
32 {
37 {
38 public:
39  using Ptr = std::shared_ptr<MutableStateSolver>;
40  using ConstPtr = std::shared_ptr<const MutableStateSolver>;
41  using UPtr = std::unique_ptr<MutableStateSolver>;
42  using ConstUPtr = std::unique_ptr<const MutableStateSolver>;
43 
44  MutableStateSolver() = default;
45  ~MutableStateSolver() override = default;
46  MutableStateSolver(const MutableStateSolver&) = default;
50 
55  virtual void setRevision(int revision) = 0;
56 
61  virtual int getRevision() const = 0;
62 
69  virtual bool addLink(const Link& link, const Joint& joint) = 0;
70 
76  virtual bool moveLink(const Joint& joint) = 0;
77 
86  virtual bool removeLink(const std::string& name) = 0;
87 
93  virtual bool replaceJoint(const Joint& joint) = 0;
94 
100  virtual bool removeJoint(const std::string& name) = 0;
101 
108  virtual bool moveJoint(const std::string& name, const std::string& parent_link) = 0;
109 
116  virtual bool changeJointOrigin(const std::string& name, const Eigen::Isometry3d& new_origin) = 0;
117 
124  virtual bool changeJointPositionLimits(const std::string& name, double lower, double upper) = 0;
125 
132  virtual bool changeJointVelocityLimits(const std::string& name, double limit) = 0;
133 
140  virtual bool changeJointAccelerationLimits(const std::string& name, double limit) = 0;
141 
148  virtual bool changeJointJerkLimits(const std::string& name, double limit) = 0;
149 
158  virtual bool insertSceneGraph(const SceneGraph& scene_graph, const Joint& joint, const std::string& prefix = "") = 0;
159 };
160 } // namespace tesseract_scene_graph
161 
162 #endif // TESSERACT_STATE_SOLVER_MUTABLE_STATE_SOLVER_H
state_solver.h
Tesseract Scene Graph State Solver Interface.
tesseract_scene_graph::MutableStateSolver::moveLink
virtual bool moveLink(const Joint &joint)=0
Move a link.
tesseract_scene_graph::MutableStateSolver::changeJointOrigin
virtual bool changeJointOrigin(const std::string &name, const Eigen::Isometry3d &new_origin)=0
Changes the "origin" transform of the joint and recomputes the associated edge.
tesseract_scene_graph::MutableStateSolver::getRevision
virtual int getRevision() const =0
Get the state solver revision number.
tesseract_scene_graph::MutableStateSolver::removeLink
virtual bool removeLink(const std::string &name)=0
Removes a link from the graph.
tesseract_scene_graph::MutableStateSolver::insertSceneGraph
virtual bool insertSceneGraph(const SceneGraph &scene_graph, const Joint &joint, const std::string &prefix="")=0
Merge a scene into the current solver.
tesseract_scene_graph::MutableStateSolver::ConstUPtr
std::unique_ptr< const MutableStateSolver > ConstUPtr
Definition: mutable_state_solver.h:42
tesseract_scene_graph::MutableStateSolver::~MutableStateSolver
~MutableStateSolver() override=default
tesseract_scene_graph::MutableStateSolver::moveJoint
virtual bool moveJoint(const std::string &name, const std::string &parent_link)=0
Move joint to new parent link.
tesseract_scene_graph::StateSolver
Definition: state_solver.h:45
tesseract_scene_graph::SceneGraph
tesseract_scene_graph::MutableStateSolver::changeJointAccelerationLimits
virtual bool changeJointAccelerationLimits(const std::string &name, double limit)=0
Changes the acceleration limits associated with a joint.
tesseract_scene_graph::MutableStateSolver::operator=
MutableStateSolver & operator=(const MutableStateSolver &)=default
tesseract_scene_graph::MutableStateSolver
A mutable state solver allows you to reconfigure the solver's links and joints.
Definition: mutable_state_solver.h:36
tesseract_scene_graph::MutableStateSolver::addLink
virtual bool addLink(const Link &link, const Joint &joint)=0
Adds a link/joint to the solver.
tesseract_scene_graph::MutableStateSolver::UPtr
std::unique_ptr< MutableStateSolver > UPtr
Definition: mutable_state_solver.h:41
tesseract_scene_graph::MutableStateSolver::setRevision
virtual void setRevision(int revision)=0
Set the state solver revision number.
tesseract_scene_graph::MutableStateSolver::MutableStateSolver
MutableStateSolver()=default
tesseract_scene_graph::MutableStateSolver::ConstPtr
std::shared_ptr< const MutableStateSolver > ConstPtr
Definition: mutable_state_solver.h:40
tesseract_scene_graph::Joint
tesseract_scene_graph::MutableStateSolver::removeJoint
virtual bool removeJoint(const std::string &name)=0
Removes a joint from the graph.
tesseract_scene_graph::MutableStateSolver::Ptr
std::shared_ptr< MutableStateSolver > Ptr
Definition: mutable_state_solver.h:39
tesseract_scene_graph::MutableStateSolver::changeJointPositionLimits
virtual bool changeJointPositionLimits(const std::string &name, double lower, double upper)=0
Changes the position limits associated with a joint.
tesseract_scene_graph::MutableStateSolver::changeJointVelocityLimits
virtual bool changeJointVelocityLimits(const std::string &name, double limit)=0
Changes the velocity limits associated with a joint.
tesseract_scene_graph
tesseract_scene_graph::MutableStateSolver::changeJointJerkLimits
virtual bool changeJointJerkLimits(const std::string &name, double limit)=0
Changes the jerk limits associated with a joint.
tesseract_scene_graph::MutableStateSolver::replaceJoint
virtual bool replaceJoint(const Joint &joint)=0
Replace and existing joint with the provided one.


tesseract_state_solver
Author(s): Levi Armstrong
autogenerated on Wed Apr 9 2025 03:03:10