Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
ofkt_state_solver.h
Go to the documentation of this file.
1
31#ifndef TESSERACT_STATE_SOLVER_OFKT_STATE_SOLVER_H
32#define TESSERACT_STATE_SOLVER_OFKT_STATE_SOLVER_H
33
36#include <Eigen/Geometry>
37#include <memory>
38#include <string>
39#include <shared_mutex>
41
44
46{
55{
56public:
57 // LCOV_EXCL_START
58 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
59 // LCOV_EXCL_STOP
60
61 using Ptr = std::shared_ptr<OFKTStateSolver>;
62 using ConstPtr = std::shared_ptr<const OFKTStateSolver>;
63 using UPtr = std::unique_ptr<OFKTStateSolver>;
64 using ConstUPtr = std::unique_ptr<const OFKTStateSolver>;
65
66 OFKTStateSolver(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& prefix = "");
67 OFKTStateSolver(const std::string& root_name);
68 ~OFKTStateSolver() override = default;
69 OFKTStateSolver(const OFKTStateSolver& other);
73
74 void setRevision(int revision) override final;
75
76 int getRevision() const override final;
77
78 void setState(const Eigen::Ref<const Eigen::VectorXd>& joint_values) override final;
79 void setState(const std::unordered_map<std::string, double>& joint_values) override final;
80 void setState(const std::vector<std::string>& joint_names,
81 const Eigen::Ref<const Eigen::VectorXd>& joint_values) override final;
82
83 SceneState getState(const Eigen::Ref<const Eigen::VectorXd>& joint_values) const override final;
84 SceneState getState(const std::unordered_map<std::string, double>& joint_values) const override final;
85 SceneState getState(const std::vector<std::string>& joint_names,
86 const Eigen::Ref<const Eigen::VectorXd>& joint_values) const override final;
87
88 SceneState getState() const override final;
89
90 SceneState getRandomState() const override final;
91
92 Eigen::MatrixXd getJacobian(const Eigen::Ref<const Eigen::VectorXd>& joint_values,
93 const std::string& link_name) const override final;
94
95 Eigen::MatrixXd getJacobian(const std::unordered_map<std::string, double>& joints_values,
96 const std::string& link_name) const override final;
97 Eigen::MatrixXd getJacobian(const std::vector<std::string>& joint_names,
98 const Eigen::Ref<const Eigen::VectorXd>& joint_values,
99 const std::string& link_name) const override final;
100
101 std::vector<std::string> getJointNames() const override final;
102
103 std::vector<std::string> getActiveJointNames() const override final;
104
105 std::string getBaseLinkName() const override final;
106
107 std::vector<std::string> getLinkNames() const override final;
108
109 std::vector<std::string> getActiveLinkNames() const override final;
110
111 std::vector<std::string> getStaticLinkNames() const override final;
112
113 bool isActiveLinkName(const std::string& link_name) const override final;
114
115 bool hasLinkName(const std::string& link_name) const override final;
116
117 tesseract_common::VectorIsometry3d getLinkTransforms() const override final;
118
119 Eigen::Isometry3d getLinkTransform(const std::string& link_name) const override final;
120
121 Eigen::Isometry3d getRelativeLinkTransform(const std::string& from_link_name,
122 const std::string& to_link_name) const override final;
123
124 tesseract_common::KinematicLimits getLimits() const override final;
125
126 bool addLink(const Link& link, const Joint& joint) override final;
127
128 bool moveLink(const Joint& joint) override final;
129
130 bool removeLink(const std::string& name) override final;
131
132 bool replaceJoint(const Joint& joint) override final;
133
134 bool removeJoint(const std::string& name) override final;
135
136 bool moveJoint(const std::string& name, const std::string& parent_link) override final;
137
138 bool changeJointOrigin(const std::string& name, const Eigen::Isometry3d& new_origin) override final;
139
140 bool changeJointPositionLimits(const std::string& name, double lower, double upper) override final;
141
142 bool changeJointVelocityLimits(const std::string& name, double limit) override final;
143
144 bool changeJointAccelerationLimits(const std::string& name, double limit) override final;
145
147 const Joint& joint,
148 const std::string& prefix = "") override final;
149
150 StateSolver::UPtr clone() const override final;
151
152private:
154 std::vector<std::string> joint_names_;
155 std::vector<std::string> active_joint_names_;
156 std::vector<std::string> link_names_;
157 std::unordered_map<std::string, OFKTNode::UPtr> nodes_;
158 std::unordered_map<std::string, OFKTNode*> link_map_;
159 tesseract_common::KinematicLimits limits_;
161 int revision_{ 0 };
164 mutable std::shared_mutex mutex_;
165
166 bool initHelper(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& prefix);
167
168 void clear();
169
171 void loadActiveLinkNamesRecursive(std::vector<std::string>& active_link_names,
172 const OFKTNode* node,
173 bool active) const;
174
176 void loadStaticLinkNamesRecursive(std::vector<std::string>& static_link_names, const OFKTNode* node) const;
177
183 void update(OFKTNode* node, bool update_required);
184
191 void update(SceneState& state, const OFKTNode* node, Eigen::Isometry3d parent_world_tf, bool update_required) const;
192
199 Eigen::MatrixXd calcJacobianHelper(const std::unordered_map<std::string, double>& joints,
200 const std::string& link_name) const;
201
207 void cloneHelper(OFKTStateSolver& cloned, const OFKTNode* node) const;
208
221 void addNode(const Joint& joint,
222 const std::string& joint_name,
223 const std::string& parent_link_name,
224 const std::string& child_link_name,
225 std::vector<JointLimits::ConstPtr>& new_joint_limits);
226
235 void removeNode(OFKTNode* node,
236 std::vector<std::string>& removed_links,
237 std::vector<std::string>& removed_joints,
238 std::vector<std::string>& removed_active_joints,
239 std::vector<long>& removed_active_joints_indices);
240
246 void moveLinkHelper(std::vector<JointLimits::ConstPtr>& new_joint_limits, const Joint& joint);
247
253 void replaceJointHelper(std::vector<JointLimits::ConstPtr>& new_joint_limits, const Joint& joint);
254
262 void removeJointHelper(const std::vector<std::string>& removed_links,
263 const std::vector<std::string>& removed_joints,
264 const std::vector<std::string>& removed_active_joints,
265 const std::vector<long>& removed_active_joints_indices);
266
271 void addNewJointLimits(const std::vector<JointLimits::ConstPtr>& new_joint_limits);
272 friend struct ofkt_builder;
273};
274
275} // namespace tesseract_scene_graph
276
277#endif // TESSERACT_STATE_SOLVER_OFKT_STATE_SOLVER_H
#define vector(a, b, c)
Definition: FloatMath.inl:3227
Definition: joint.h:281
A mutable state solver allows you to reconfigure the solver's links and joints.
Definition: mutable_state_solver.h:37
The OFKT node is contains multiple trasformation which are described below.
Definition: ofkt_node.h:56
An implementation of the Optimized Forward Kinematic Tree as a stat solver.
Definition: ofkt_state_solver.h:55
bool hasLinkName(const std::string &link_name) const override final
Check if link name exists.
Definition: ofkt_state_solver.cpp:407
std::vector< std::string > joint_names_
Definition: ofkt_state_solver.h:154
OFKTNode::UPtr root_
Definition: ofkt_state_solver.h:160
void removeJointHelper(const std::vector< std::string > &removed_links, const std::vector< std::string > &removed_joints, const std::vector< std::string > &removed_active_joints, const std::vector< long > &removed_active_joints_indices)
This will clean up member variables joint_names_ and limits_.
Definition: ofkt_state_solver.cpp:941
std::vector< std::string > link_names_
Definition: ofkt_state_solver.h:156
std::shared_ptr< const OFKTStateSolver > ConstPtr
Definition: ofkt_state_solver.h:62
bool moveJoint(const std::string &name, const std::string &parent_link) override final
Move joint to new parent link.
Definition: ofkt_state_solver.cpp:591
tesseract_common::KinematicLimits limits_
Definition: ofkt_state_solver.h:159
void loadStaticLinkNamesRecursive(std::vector< std::string > &static_link_names, const OFKTNode *node) const
load the static link names
Definition: ofkt_state_solver.cpp:771
std::string getBaseLinkName() const override final
Get the base link name.
Definition: ofkt_state_solver.cpp:370
int revision_
Definition: ofkt_state_solver.h:161
bool changeJointAccelerationLimits(const std::string &name, double limit) override final
Changes the acceleration limits associated with a joint.
Definition: ofkt_state_solver.cpp:672
bool moveLink(const Joint &joint) override final
Move a link.
Definition: ofkt_state_solver.cpp:501
void cloneHelper(OFKTStateSolver &cloned, const OFKTNode *node) const
A helper function used for cloning the OFKTStateSolver.
Definition: ofkt_state_solver.cpp:76
Eigen::MatrixXd getJacobian(const Eigen::Ref< const Eigen::VectorXd > &joint_values, const std::string &link_name) const override final
Get the jacobian of the solver given the joint values.
Definition: ofkt_state_solver.cpp:290
OFKTStateSolver & operator=(const OFKTStateSolver &other)
Definition: ofkt_state_solver.cpp:155
Eigen::Isometry3d getRelativeLinkTransform(const std::string &from_link_name, const std::string &to_link_name) const override final
Get transform between two links using the current state.
Definition: ofkt_state_solver.cpp:428
StateSolver::UPtr clone() const override final
This should clone the object so it may be used in a multi threaded application where each thread woul...
Definition: ofkt_state_solver.cpp:169
OFKTStateSolver & operator=(OFKTStateSolver &&)=delete
void loadActiveLinkNamesRecursive(std::vector< std::string > &active_link_names, const OFKTNode *node, bool active) const
load the active link names
Definition: ofkt_state_solver.cpp:744
SceneState getRandomState() const override final
Get the random state of the environment.
Definition: ofkt_state_solver.cpp:284
tesseract_common::KinematicLimits getLimits() const override final
Getter for kinematic limits.
Definition: ofkt_state_solver.cpp:434
std::unordered_map< std::string, OFKTNode::UPtr > nodes_
Definition: ofkt_state_solver.h:157
std::vector< std::string > getLinkNames() const override final
Get the vector of link names.
Definition: ofkt_state_solver.cpp:376
Eigen::MatrixXd calcJacobianHelper(const std::unordered_map< std::string, double > &joints, const std::string &link_name) const
Given a set of joint values calculate the jacobian for the provided link_name.
Definition: ofkt_state_solver.cpp:324
std::vector< std::string > getActiveJointNames() const override final
Get the vector of joint names which align with the limits.
Definition: ofkt_state_solver.cpp:364
void setRevision(int revision) override final
Set the state solver revision number.
Definition: ofkt_state_solver.cpp:175
void removeNode(OFKTNode *node, std::vector< std::string > &removed_links, std::vector< std::string > &removed_joints, std::vector< std::string > &removed_active_joints, std::vector< long > &removed_active_joints_indices)
Remove a node and all of its children.
Definition: ofkt_state_solver.cpp:1087
std::unique_ptr< OFKTStateSolver > UPtr
Definition: ofkt_state_solver.h:63
tesseract_common::VectorIsometry3d getLinkTransforms() const override final
Get all of the links transforms.
Definition: ofkt_state_solver.cpp:413
void replaceJointHelper(std::vector< JointLimits::ConstPtr > &new_joint_limits, const Joint &joint)
This is a helper function for replacing a joint.
Definition: ofkt_state_solver.cpp:923
void update(OFKTNode *node, bool update_required)
This update the local and world transforms.
Definition: ofkt_state_solver.cpp:783
bool isActiveLinkName(const std::string &link_name) const override final
Check if link is an active link.
Definition: ofkt_state_solver.cpp:400
bool replaceJoint(const Joint &joint) override final
Replace and existing joint with the provided one.
Definition: ofkt_state_solver.cpp:467
bool removeJoint(const std::string &name) override final
Removes a joint from the graph.
Definition: ofkt_state_solver.cpp:559
bool changeJointPositionLimits(const std::string &name, double lower, double upper) override final
Changes the position limits associated with a joint.
Definition: ofkt_state_solver.cpp:637
int getRevision() const override final
Get the state solver revision number.
Definition: ofkt_state_solver.cpp:181
Eigen::Isometry3d getLinkTransform(const std::string &link_name) const override final
Get the transform corresponding to the link.
Definition: ofkt_state_solver.cpp:423
bool initHelper(const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &prefix)
Definition: ofkt_state_solver.cpp:838
bool insertSceneGraph(const SceneGraph &scene_graph, const Joint &joint, const std::string &prefix="") override final
Merge a scene into the current solver.
Definition: ofkt_state_solver.cpp:689
std::vector< std::string > getJointNames() const override final
Get the vector of joint names.
Definition: ofkt_state_solver.cpp:358
bool addLink(const Link &link, const Joint &joint) override final
Adds a link/joint to the solver.
Definition: ofkt_state_solver.cpp:440
SceneState current_state_
Definition: ofkt_state_solver.h:153
std::unique_ptr< const OFKTStateSolver > ConstUPtr
Definition: ofkt_state_solver.h:64
SceneState getState() const override final
Get the current state of the scene.
Definition: ofkt_state_solver.cpp:278
std::vector< std::string > getStaticLinkNames() const override final
Get a vector of static link names in the environment.
Definition: ofkt_state_solver.cpp:391
void addNode(const Joint &joint, const std::string &joint_name, const std::string &parent_link_name, const std::string &child_link_name, std::vector< JointLimits::ConstPtr > &new_joint_limits)
Add a node to the tree.
Definition: ofkt_state_solver.cpp:1001
bool changeJointVelocityLimits(const std::string &name, double limit) override final
Changes the velocity limits associated with a joint.
Definition: ofkt_state_solver.cpp:655
void addNewJointLimits(const std::vector< JointLimits::ConstPtr > &new_joint_limits)
appends the new joint limits
Definition: ofkt_state_solver.cpp:1118
void moveLinkHelper(std::vector< JointLimits::ConstPtr > &new_joint_limits, const Joint &joint)
This a helper function for moving a link.
Definition: ofkt_state_solver.cpp:880
bool removeLink(const std::string &name) override final
Removes a link from the graph.
Definition: ofkt_state_solver.cpp:527
OFKTStateSolver(OFKTStateSolver &&)=delete
std::vector< std::string > getActiveLinkNames() const override final
Get the vector of active link names.
Definition: ofkt_state_solver.cpp:382
bool changeJointOrigin(const std::string &name, const Eigen::Isometry3d &new_origin) override final
Changes the "origin" transform of the joint and recomputes the associated edge.
Definition: ofkt_state_solver.cpp:620
std::shared_ptr< OFKTStateSolver > Ptr
Definition: ofkt_state_solver.h:61
std::vector< std::string > active_joint_names_
Definition: ofkt_state_solver.h:155
void clear()
Definition: ofkt_state_solver.cpp:187
void setState(const Eigen::Ref< const Eigen::VectorXd > &joint_values) override final
Set the current state of the solver.
Definition: ofkt_state_solver.cpp:201
std::shared_mutex mutex_
The state solver can be accessed from multiple threads, need use mutex throughout.
Definition: ofkt_state_solver.h:164
std::unordered_map< std::string, OFKTNode * > link_map_
Definition: ofkt_state_solver.h:158
Definition: graph.h:125
Definition: state_solver.h:46
auto scene_graph
Definition: ikfast_kinematics_7dof_unit.cpp:51
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Tesseract Scene Graph Mutable State Solver Interface .
Definition: create_convex_hull.cpp:36
Definition: allowed_collision_matrix.h:16
Definition: graph.h:82
A implementation of the Optimized Forward Kinematic Tree Node.
This holds a state of the scene.
Definition: scene_state.h:54
Every time a vertex is visited for the first time add a new node to the tree.
Definition: ofkt_state_solver.cpp:45
joint_state joint_names
Definition: tesseract_common_serialization_unit.cpp:75
j lower
Definition: tesseract_scene_graph_joint_unit.cpp:39
joint_1 mimic joint_name
Definition: tesseract_scene_graph_joint_unit.cpp:163
j upper
Definition: tesseract_scene_graph_joint_unit.cpp:40
object child_link_name
Definition: tesseract_scene_graph_serialization_unit.cpp:82
object parent_link_name
Definition: tesseract_scene_graph_serialization_unit.cpp:83
object joints["j_1"]
Definition: tesseract_scene_graph_serialization_unit.cpp:224