Exotica
kinematic_tree.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #ifndef EXOTICA_CORE_KINEMATIC_TREE_H_
31 #define EXOTICA_CORE_KINEMATIC_TREE_H_
32 
33 #include <map>
34 #include <random>
35 #include <string>
36 #include <vector>
37 
38 #include <moveit/robot_model/robot_model.h>
39 #include <tf/transform_datatypes.h>
40 #include <visualization_msgs/MarkerArray.h>
41 #include <Eigen/Eigen>
42 #include <kdl/jacobian.hpp>
43 #include <kdl/tree.hpp>
44 
46 
47 namespace exotica
48 {
50 {
51  FIXED = 0,
52  FLOATING = 10,
53  PLANAR = 20
54 };
55 
57 {
58  KIN_FK = 0,
59  KIN_J = 2,
61  KIN_H = 8
62 };
63 
65 {
68 };
69 
70 constexpr double inf = std::numeric_limits<double>::infinity();
71 constexpr double pi = M_PI;
72 
74 {
75  return static_cast<KinematicRequestFlags>(static_cast<int>(a) | static_cast<int>(b));
76 }
77 
79 {
80  return static_cast<KinematicRequestFlags>(static_cast<int>(a) & static_cast<int>(b));
81 }
82 
84 {
86  KinematicFrameRequest(std::string _frame_A_link_name, KDL::Frame _frame_A_offset = KDL::Frame(), std::string _frame_B_link_name = "", KDL::Frame _frame_B_offset = KDL::Frame());
87  std::string frame_A_link_name;
88  KDL::Frame frame_A_offset;
89  std::string frame_B_link_name;
90  KDL::Frame frame_B_offset;
91 };
92 
94 {
97  std::vector<KinematicFrameRequest> frames; // The segments to which the end-effectors are attached
98 };
99 
101 {
102  std::weak_ptr<KinematicElement> frame_A;
103  KDL::Frame frame_A_offset;
104  std::weak_ptr<KinematicElement> frame_B;
105  KDL::Frame frame_B_offset;
106  KDL::Frame temp_AB;
107  KDL::Frame temp_A;
108  KDL::Frame temp_B;
109 };
110 
114 {
116  KinematicResponse(KinematicRequestFlags _flags, int _size, int _N = 0);
118  std::vector<KinematicFrame> frame;
119  Eigen::VectorXd x;
124 };
125 
128 {
129 public:
131  KinematicSolution(int start, int length);
132  void Create(std::shared_ptr<KinematicResponse> solution);
133  int start = -1;
134  int length = -1;
135  Eigen::Map<Eigen::VectorXd> X{nullptr, 0};
136  Eigen::Map<ArrayFrame> Phi{nullptr, 0};
137  Eigen::Map<ArrayTwist> Phi_dot{nullptr, 0};
138  Eigen::Map<ArrayJacobian> jacobian{nullptr, 0};
139  Eigen::Map<ArrayHessian> hessian{nullptr, 0};
140 };
141 
142 class KinematicTree : public Uncopyable
143 {
144 public:
145  void Instantiate(const std::string& joint_group, robot_model::RobotModelPtr model, const std::string& name);
146  const std::string& GetRootFrameName() const;
147  const std::string& GetRootJointName() const;
148  robot_model::RobotModelPtr GetRobotModel() const;
149  BaseType GetModelBaseType() const;
151  std::shared_ptr<KinematicResponse> RequestFrames(const KinematicsRequest& request);
153  void ResetJointLimits();
154  const Eigen::MatrixXd& GetJointLimits() const { return joint_limits_; }
159  void SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector<double>& lower, const std::vector<double>& upper);
160  void SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector<double>& lower, const std::vector<double>& upper, const std::vector<double>& velocity, const std::vector<double>& acceleration);
161  void SetPlanarBaseLimitsPosXYEulerZ(const std::vector<double>& lower, const std::vector<double>& upper);
162  void SetPlanarBaseLimitsPosXYEulerZ(const std::vector<double>& lower, const std::vector<double>& upper, const std::vector<double>& velocity, const std::vector<double>& acceleration);
163  std::map<std::string, std::vector<double>> GetUsedJointLimits() const;
164  const bool& HasAccelerationLimits() const { return has_acceleration_limit_; }
165  const Eigen::VectorXd& GetAccelerationLimits() const { return acceleration_limits_; }
166  const Eigen::VectorXd& GetVelocityLimits() const { return velocity_limits_; }
167  int GetNumControlledJoints() const;
168  int GetNumModelJoints() const;
169  void PublishFrames(const std::string& tf_prefix = "exotica");
170 
171  const std::vector<std::string>& GetControlledJointNames() const
172  {
174  }
175 
176  const std::vector<std::string>& GetControlledLinkNames() const
177  {
178  return controlled_link_names_;
179  }
180 
181  const std::vector<std::string>& GetModelJointNames() const
182  {
183  return model_joints_names_;
184  }
185 
186  const std::vector<std::string>& GetModelLinkNames() const
187  {
188  return model_link_names_;
189  }
190 
191  bool HasModelLink(const std::string& link) const;
192 
193  Eigen::VectorXd GetControlledLinkMass() const;
194 
195  KDL::Frame FK(KinematicFrame& frame) const;
196  KDL::Frame FK(std::shared_ptr<KinematicElement> element_A, const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B, const KDL::Frame& offset_b) const;
197  KDL::Frame FK(const std::string& element_A, const KDL::Frame& offset_a, const std::string& element_B, const KDL::Frame& offset_b) const;
198  Eigen::MatrixXd Jacobian(std::shared_ptr<KinematicElement> element_A, const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B, const KDL::Frame& offset_b) const;
199  Eigen::MatrixXd Jacobian(const std::string& element_A, const KDL::Frame& offset_a, const std::string& element_B, const KDL::Frame& offset_b) const;
200  exotica::Hessian Hessian(std::shared_ptr<KinematicElement> element_A, const KDL::Frame& offset_a, std::shared_ptr<KinematicElement> element_B, const KDL::Frame& offset_b) const;
201  exotica::Hessian Hessian(const std::string& element_A, const KDL::Frame& offset_a, const std::string& element_B, const KDL::Frame& offset_b) const;
202 
203  void ResetModel();
204  std::shared_ptr<KinematicElement> AddElement(const std::string& name, const Eigen::Isometry3d& transform, const std::string& parent = "", shapes::ShapeConstPtr shape = shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia& inertia = KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d& color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector<VisualElement>& visual = {}, bool is_controlled = false);
205  std::shared_ptr<KinematicElement> AddEnvironmentElement(const std::string& name, const Eigen::Isometry3d& transform, const std::string& parent = "", shapes::ShapeConstPtr shape = shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia& inertia = KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d& color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector<VisualElement>& visual = {}, bool is_controlled = false);
206  std::shared_ptr<KinematicElement> AddElement(const std::string& name, const Eigen::Isometry3d& transform, const std::string& parent, const std::string& shape_resource_path, Eigen::Vector3d scale = Eigen::Vector3d::Ones(), const KDL::RigidBodyInertia& inertia = KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d& color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector<VisualElement>& visual = {}, bool is_controlled = false);
207  void UpdateModel();
208  void ChangeParent(const std::string& name, const std::string& parent, const KDL::Frame& pose, bool relative);
209  int IsControlled(std::shared_ptr<KinematicElement> joint);
210  int IsControlledLink(const std::string& link_name);
211 
212  Eigen::VectorXd GetModelState() const;
213  std::map<std::string, double> GetModelStateMap() const;
214 
219  std::vector<std::string> GetKinematicChain(const std::string& begin, const std::string& end) const;
220 
225  std::vector<std::string> GetKinematicChainLinks(const std::string& begin, const std::string& end) const;
226 
228  void SetModelState(const std::map<std::string, double>& x);
229  Eigen::VectorXd GetControlledState() const;
230 
231  const std::vector<std::weak_ptr<KinematicElement>>& GetTree() const { return tree_; }
232  const std::vector<std::shared_ptr<KinematicElement>>& GetModelTree() const { return model_tree_; }
233  const std::map<std::string, std::weak_ptr<KinematicElement>>& GetTreeMap() const { return tree_map_; }
234  const std::map<std::string, std::weak_ptr<KinematicElement>>& GetCollisionTreeMap() const { return collision_tree_map_; }
235  bool DoesLinkWithNameExist(std::string name) const;
236  std::shared_ptr<KinematicElement> FindKinematicElementByName(const std::string& frame_name);
237 
238  const std::vector<std::weak_ptr<KinematicElement>>& GetControlledJoints() const { return controlled_joints_; }
239  const std::map<std::string, std::weak_ptr<KinematicElement>>& GetControlledJointsMap() const { return controlled_joints_map_; }
240  const std::map<std::string, std::weak_ptr<KinematicElement>>& GetModelJointsMap() const { return model_joints_map_; }
241  std::map<std::string, shapes::ShapeType> GetCollisionObjectTypes() const;
242 
245  void SetSeed(const uint_fast32_t seed) { generator_.seed(seed); }
247  Eigen::VectorXd GetRandomControlledState();
248 
249  void SetKinematicResponse(std::shared_ptr<KinematicResponse> response_in) { solution_ = response_in; }
250  std::shared_ptr<KinematicResponse> GetKinematicResponse() { return solution_; }
251  bool debug = false;
252 
253 private:
254  void BuildTree(const KDL::Tree& RobotKinematics);
255  void AddElementFromSegmentMapIterator(KDL::SegmentMap::const_iterator segment, std::shared_ptr<KinematicElement> parent);
256  void UpdateTree();
257  void UpdateFK();
258  void UpdateJ();
259  void ComputeJ(KinematicFrame& frame, KDL::Jacobian& jacobian) const;
260  void UpdateH();
261  void ComputeH(KinematicFrame& frame, const KDL::Jacobian& jacobian, exotica::Hessian& hessian) const;
262 
263  // Joint limits
264  // TODO: Add effort limits
265  Eigen::MatrixXd joint_limits_;
266  Eigen::VectorXd velocity_limits_;
267  Eigen::VectorXd acceleration_limits_;
269  void UpdateJointLimits();
270 
271  // Random state generation
272  std::random_device rd_;
273  std::mt19937 generator_;
274  std::vector<std::uniform_real_distribution<double>> random_state_distributions_;
275 
280  int state_size_ = -1;
281  Eigen::VectorXd tree_state_;
282  robot_model::RobotModelPtr model_;
283  std::string root_joint_name_ = "";
284  std::vector<std::weak_ptr<KinematicElement>> tree_;
285  std::vector<std::shared_ptr<KinematicElement>> model_tree_;
286  std::vector<std::shared_ptr<KinematicElement>> environment_tree_;
287  std::map<std::string, std::weak_ptr<KinematicElement>> tree_map_;
288  std::map<std::string, std::weak_ptr<KinematicElement>> collision_tree_map_;
289  std::shared_ptr<KinematicElement> root_;
290  std::vector<std::weak_ptr<KinematicElement>> controlled_joints_;
291  std::map<std::string, std::weak_ptr<KinematicElement>> controlled_joints_map_;
292  std::map<std::string, std::weak_ptr<KinematicElement>> model_joints_map_;
293  std::vector<std::string> model_joints_names_;
294  std::vector<std::string> controlled_joints_names_;
295  std::vector<std::string> model_link_names_;
296  std::vector<std::string> controlled_link_names_;
297  std::shared_ptr<KinematicResponse> solution_ = std::make_shared<KinematicResponse>();
299 
300  std::vector<tf::StampedTransform> debug_tree_;
301  std::vector<tf::StampedTransform> debug_frames_;
302  ros::Publisher shapes_pub_;
303  ros::Publisher octomap_pub_;
305  visualization_msgs::MarkerArray marker_array_msg_;
306  std::string name_;
307 };
308 } // namespace exotica
309 
310 #endif // EXOTICA_CORE_KINEMATIC_TREE_H_
exotica::KinematicTree::GetControlledBaseType
BaseType GetControlledBaseType() const
exotica::KIN_H
@ KIN_H
Definition: kinematic_tree.h:61
exotica::KinematicTree::Hessian
exotica::Hessian Hessian(std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
exotica::KinematicTree::RequestFrames
std::shared_ptr< KinematicResponse > RequestFrames(const KinematicsRequest &request)
exotica::KinematicsRequest::frames
std::vector< KinematicFrameRequest > frames
Definition: kinematic_tree.h:97
exotica::KinematicTree::Update
void Update(Eigen::VectorXdRefConst x)
exotica::KinematicTree::UpdateTree
void UpdateTree()
exotica::KinematicSolution::Phi
Eigen::Map< ArrayFrame > Phi
Definition: kinematic_tree.h:136
exotica::KinematicTree::num_controlled_joints_
int num_controlled_joints_
Number of controlled joints in the joint group.
Definition: kinematic_tree.h:278
exotica::KinematicTree::marker_array_msg_
visualization_msgs::MarkerArray marker_array_msg_
Definition: kinematic_tree.h:305
exotica::KinematicTree::DoesLinkWithNameExist
bool DoesLinkWithNameExist(std::string name) const
Checks whether a link with this name exists in any of the trees.
exotica::KinematicResponse::Phi
ArrayFrame Phi
Definition: kinematic_tree.h:120
exotica::PLANAR
@ PLANAR
Definition: kinematic_tree.h:53
exotica::KinematicTree::IsControlledLink
int IsControlledLink(const std::string &link_name)
exotica::KinematicSolution::KinematicSolution
KinematicSolution()
exotica::KinematicTree::GetKinematicResponse
std::shared_ptr< KinematicResponse > GetKinematicResponse()
Definition: kinematic_tree.h:250
exotica::Uncopyable
Definition: uncopyable.h:35
exotica::KinematicTree::model_link_names_
std::vector< std::string > model_link_names_
Definition: kinematic_tree.h:295
exotica::KinematicTree::rd_
std::random_device rd_
Definition: kinematic_tree.h:272
exotica::KinematicTree::GetRootFrameName
const std::string & GetRootFrameName() const
exotica::BaseType
BaseType
Definition: kinematic_tree.h:49
exotica::KinematicResponse::flags
KinematicRequestFlags flags
Definition: kinematic_tree.h:117
exotica::KinematicTree::acceleration_limits_
Eigen::VectorXd acceleration_limits_
Definition: kinematic_tree.h:267
exotica::KinematicTree::SetJointAccelerationLimits
void SetJointAccelerationLimits(Eigen::VectorXdRefConst acceleration_in)
exotica::KinematicTree::GetModelJointsMap
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetModelJointsMap() const
Definition: kinematic_tree.h:240
exotica::KinematicTree::Jacobian
Eigen::MatrixXd Jacobian(std::shared_ptr< KinematicElement > element_A, const KDL::Frame &offset_a, std::shared_ptr< KinematicElement > element_B, const KDL::Frame &offset_b) const
exotica::KinematicTree::GetKinematicChainLinks
std::vector< std::string > GetKinematicChainLinks(const std::string &begin, const std::string &end) const
GetKinematicChainLinks get the links between begin and end of kinematic chain.
exotica::KinematicResponse::jacobian
ArrayJacobian jacobian
Definition: kinematic_tree.h:122
exotica::KinematicTree::GetJointLimits
const Eigen::MatrixXd & GetJointLimits() const
Definition: kinematic_tree.h:154
exotica::KinematicResponse::KinematicResponse
KinematicResponse()
exotica::KinematicTree::state_size_
int state_size_
Definition: kinematic_tree.h:280
exotica::KinematicFrameRequest
Definition: kinematic_tree.h:83
exotica::KinematicTree::model_joints_names_
std::vector< std::string > model_joints_names_
Definition: kinematic_tree.h:293
exotica::KinematicTree::generator_
std::mt19937 generator_
Definition: kinematic_tree.h:273
exotica::KinematicFrame::temp_A
KDL::Frame temp_A
Definition: kinematic_tree.h:107
exotica::KinematicTree::model_tree_
std::vector< std::shared_ptr< KinematicElement > > model_tree_
Definition: kinematic_tree.h:285
exotica::KIN_J
@ KIN_J
Definition: kinematic_tree.h:59
exotica::KinematicTree::UpdateModel
void UpdateModel()
exotica::KinematicFrameRequest::frame_A_link_name
std::string frame_A_link_name
Definition: kinematic_tree.h:87
exotica::KinematicTree::ChangeParent
void ChangeParent(const std::string &name, const std::string &parent, const KDL::Frame &pose, bool relative)
exotica::KinematicTree::GetNumControlledJoints
int GetNumControlledJoints() const
exotica::KinematicFrameRequest::frame_B_offset
KDL::Frame frame_B_offset
Definition: kinematic_tree.h:90
exotica::KinematicTree::controlled_joints_map_
std::map< std::string, std::weak_ptr< KinematicElement > > controlled_joints_map_
Definition: kinematic_tree.h:291
exotica::KinematicTree::GetModelBaseType
BaseType GetModelBaseType() const
exotica::KinematicTree::GetTreeMap
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetTreeMap() const
Definition: kinematic_tree.h:233
exotica::KinematicTree::HasModelLink
bool HasModelLink(const std::string &link) const
exotica::KinematicTree::FindKinematicElementByName
std::shared_ptr< KinematicElement > FindKinematicElementByName(const std::string &frame_name)
exotica::KinematicTree::SetKinematicResponse
void SetKinematicResponse(std::shared_ptr< KinematicResponse > response_in)
Definition: kinematic_tree.h:249
exotica::KinematicTree::debug_scene_changed_
bool debug_scene_changed_
Definition: kinematic_tree.h:304
exotica::KinematicTree::solution_
std::shared_ptr< KinematicResponse > solution_
Definition: kinematic_tree.h:297
exotica::KinematicTree::AddElement
std::shared_ptr< KinematicElement > AddElement(const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
exotica
Definition: cartpole_dynamics_solver.h:38
exotica::FLOATING
@ FLOATING
Definition: kinematic_tree.h:52
exotica::KinematicSolution::Phi_dot
Eigen::Map< ArrayTwist > Phi_dot
Definition: kinematic_tree.h:137
exotica::Hessian
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
Definition: conversions.h:154
exotica::KinematicTree::GetControlledJointsMap
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetControlledJointsMap() const
Definition: kinematic_tree.h:239
exotica::pi
constexpr double pi
Definition: kinematic_tree.h:71
exotica::KinematicTree::name_
std::string name_
Definition: kinematic_tree.h:306
exotica::KinematicTree::GetModelJointNames
const std::vector< std::string > & GetModelJointNames() const
Definition: kinematic_tree.h:181
exotica::KinematicTree::GetModelStateMap
std::map< std::string, double > GetModelStateMap() const
exotica::KinematicTree::GetCollisionTreeMap
const std::map< std::string, std::weak_ptr< KinematicElement > > & GetCollisionTreeMap() const
Definition: kinematic_tree.h:234
exotica::KinematicTree::model_joints_map_
std::map< std::string, std::weak_ptr< KinematicElement > > model_joints_map_
Definition: kinematic_tree.h:292
exotica::KinematicFrame::frame_B_offset
KDL::Frame frame_B_offset
Definition: kinematic_tree.h:105
exotica::KinematicTree::GetModelLinkNames
const std::vector< std::string > & GetModelLinkNames() const
Definition: kinematic_tree.h:186
exotica::KinematicTree::AddEnvironmentElement
std::shared_ptr< KinematicElement > AddEnvironmentElement(const std::string &name, const Eigen::Isometry3d &transform, const std::string &parent="", shapes::ShapeConstPtr shape=shapes::ShapeConstPtr(nullptr), const KDL::RigidBodyInertia &inertia=KDL::RigidBodyInertia::Zero(), const Eigen::Vector4d &color=Eigen::Vector4d(0.5, 0.5, 0.5, 1.0), const std::vector< VisualElement > &visual={}, bool is_controlled=false)
exotica::KinematicTree::BuildTree
void BuildTree(const KDL::Tree &RobotKinematics)
exotica::LIMIT_POSITION_UPPER
@ LIMIT_POSITION_UPPER
Definition: kinematic_tree.h:67
exotica::KinematicTree::ResetModel
void ResetModel()
exotica::KinematicTree::GetRobotModel
robot_model::RobotModelPtr GetRobotModel() const
exotica::KIN_FK
@ KIN_FK
Definition: kinematic_tree.h:58
exotica::KinematicsRequest::flags
KinematicRequestFlags flags
Definition: kinematic_tree.h:96
exotica::KinematicFrame::temp_AB
KDL::Frame temp_AB
Definition: kinematic_tree.h:106
exotica::KinematicFrameRequest::KinematicFrameRequest
KinematicFrameRequest()
exotica::KinematicTree::num_joints_
int num_joints_
Number of joints of the model (including floating/planar base, passive joints, and uncontrolled joint...
Definition: kinematic_tree.h:279
exotica::KinematicTree::ComputeH
void ComputeH(KinematicFrame &frame, const KDL::Jacobian &jacobian, exotica::Hessian &hessian) const
exotica::KinematicTree::model_base_type_
BaseType model_base_type_
Definition: kinematic_tree.h:276
exotica::KinematicFrame
Definition: kinematic_tree.h:100
exotica::KinematicTree::SetJointLimitsLower
void SetJointLimitsLower(Eigen::VectorXdRefConst lower_in)
exotica::KinematicSolution::jacobian
Eigen::Map< ArrayJacobian > jacobian
Definition: kinematic_tree.h:138
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
exotica::KinematicTree::debug_frames_
std::vector< tf::StampedTransform > debug_frames_
Definition: kinematic_tree.h:301
exotica::KinematicRequestFlags
KinematicRequestFlags
Definition: kinematic_tree.h:56
exotica::KinematicTree::UpdateFK
void UpdateFK()
exotica::KinematicTree::debug_tree_
std::vector< tf::StampedTransform > debug_tree_
Definition: kinematic_tree.h:300
exotica::KinematicTree::UpdateJ
void UpdateJ()
exotica::KinematicTree::debug
bool debug
Definition: kinematic_tree.h:251
exotica::KinematicsRequest::KinematicsRequest
KinematicsRequest()
exotica::KinematicResponse::x
Eigen::VectorXd x
Definition: kinematic_tree.h:119
exotica::ArrayHessian
Eigen::Array< Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 >, Eigen::Dynamic, 1 > ArrayHessian
Definition: conversions.h:155
exotica::inf
constexpr double inf
Definition: kinematic_tree.h:70
exotica::KinematicTree::controlled_joints_
std::vector< std::weak_ptr< KinematicElement > > controlled_joints_
Definition: kinematic_tree.h:290
exotica::KinematicTree::environment_tree_
std::vector< std::shared_ptr< KinematicElement > > environment_tree_
Definition: kinematic_tree.h:286
exotica::KinematicTree::ComputeJ
void ComputeJ(KinematicFrame &frame, KDL::Jacobian &jacobian) const
exotica::KinematicTree::GetRandomControlledState
Eigen::VectorXd GetRandomControlledState()
Random state generation.
exotica::KinematicTree::GetControlledState
Eigen::VectorXd GetControlledState() const
exotica::KinematicTree::IsControlled
int IsControlled(std::shared_ptr< KinematicElement > joint)
exotica::KinematicTree::flags_
KinematicRequestFlags flags_
Definition: kinematic_tree.h:298
exotica::KinematicTree::GetAccelerationLimits
const Eigen::VectorXd & GetAccelerationLimits() const
Definition: kinematic_tree.h:165
exotica::KinematicTree::GetControlledLinkNames
const std::vector< std::string > & GetControlledLinkNames() const
Definition: kinematic_tree.h:176
exotica::KinematicSolution::hessian
Eigen::Map< ArrayHessian > hessian
Definition: kinematic_tree.h:139
exotica::KinematicTree::tree_map_
std::map< std::string, std::weak_ptr< KinematicElement > > tree_map_
Definition: kinematic_tree.h:287
exotica::KinematicTree::GetModelState
Eigen::VectorXd GetModelState() const
exotica::KinematicTree::root_joint_name_
std::string root_joint_name_
Definition: kinematic_tree.h:283
exotica::KinematicTree::AddElementFromSegmentMapIterator
void AddElementFromSegmentMapIterator(KDL::SegmentMap::const_iterator segment, std::shared_ptr< KinematicElement > parent)
exotica::KIN_FK_VEL
@ KIN_FK_VEL
Definition: kinematic_tree.h:60
exotica::KinematicTree::controlled_joints_names_
std::vector< std::string > controlled_joints_names_
Definition: kinematic_tree.h:294
exotica::KinematicFrame::frame_A_offset
KDL::Frame frame_A_offset
Definition: kinematic_tree.h:103
exotica::KinematicTree
Definition: kinematic_tree.h:142
exotica::KinematicTree::GetUsedJointLimits
std::map< std::string, std::vector< double > > GetUsedJointLimits() const
exotica::KinematicFrame::frame_A
std::weak_ptr< KinematicElement > frame_A
Definition: kinematic_tree.h:102
exotica::KinematicTree::GetControlledJointNames
const std::vector< std::string > & GetControlledJointNames() const
Definition: kinematic_tree.h:171
exotica::KinematicTree::UpdateH
void UpdateH()
exotica::KinematicTree::GetModelTree
const std::vector< std::shared_ptr< KinematicElement > > & GetModelTree() const
Definition: kinematic_tree.h:232
exotica::KinematicTree::GetVelocityLimits
const Eigen::VectorXd & GetVelocityLimits() const
Definition: kinematic_tree.h:166
exotica::KinematicTree::SetJointVelocityLimits
void SetJointVelocityLimits(Eigen::VectorXdRefConst velocity_in)
exotica::KinematicTree::GetKinematicChain
std::vector< std::string > GetKinematicChain(const std::string &begin, const std::string &end) const
GetKinematicChain get list of joints in a kinematic chain.
exotica::KinematicFrame::temp_B
KDL::Frame temp_B
Definition: kinematic_tree.h:108
exotica::KinematicSolution::length
int length
Definition: kinematic_tree.h:134
exotica::KinematicFrame::frame_B
std::weak_ptr< KinematicElement > frame_B
Definition: kinematic_tree.h:104
exotica::KinematicTree::collision_tree_map_
std::map< std::string, std::weak_ptr< KinematicElement > > collision_tree_map_
Definition: kinematic_tree.h:288
exotica::KinematicTree::HasAccelerationLimits
const bool & HasAccelerationLimits() const
Definition: kinematic_tree.h:164
exotica::KinematicTree::SetFloatingBaseLimitsPosXYZEulerZYX
void SetFloatingBaseLimitsPosXYZEulerZYX(const std::vector< double > &lower, const std::vector< double > &upper)
exotica::KinematicSolution::Create
void Create(std::shared_ptr< KinematicResponse > solution)
exotica::KinematicTree::controlled_link_names_
std::vector< std::string > controlled_link_names_
Definition: kinematic_tree.h:296
exotica::KinematicTree::controlled_base_type_
BaseType controlled_base_type_
Definition: kinematic_tree.h:277
exotica::KinematicResponse
The KinematicResponse is the container to keep kinematic update data. The corresponding KinematicSolu...
Definition: kinematic_tree.h:113
exotica::KinematicFrameRequest::frame_A_offset
KDL::Frame frame_A_offset
Definition: kinematic_tree.h:88
exotica::KinematicsRequest
Definition: kinematic_tree.h:93
exotica::ArrayJacobian
Eigen::Array< KDL::Jacobian, Eigen::Dynamic, 1 > ArrayJacobian
Definition: conversions.h:153
exotica::KinematicSolution::X
Eigen::Map< Eigen::VectorXd > X
Definition: kinematic_tree.h:135
exotica::KinematicTree::shapes_pub_
ros::Publisher shapes_pub_
Definition: kinematic_tree.h:302
exotica::KinematicTree::velocity_limits_
Eigen::VectorXd velocity_limits_
Definition: kinematic_tree.h:266
exotica::KinematicTree::GetTree
const std::vector< std::weak_ptr< KinematicElement > > & GetTree() const
Definition: kinematic_tree.h:231
exotica::operator|
KinematicRequestFlags operator|(KinematicRequestFlags a, KinematicRequestFlags b)
Definition: kinematic_tree.h:73
exotica::KinematicTree::SetSeed
void SetSeed(const uint_fast32_t seed)
SetSeed sets the seed of the random generator for deterministic joint state sampling.
Definition: kinematic_tree.h:245
exotica::operator&
KinematicRequestFlags operator&(KinematicRequestFlags a, KinematicRequestFlags b)
Definition: kinematic_tree.h:78
exotica::KinematicTree::SetPlanarBaseLimitsPosXYEulerZ
void SetPlanarBaseLimitsPosXYEulerZ(const std::vector< double > &lower, const std::vector< double > &upper)
exotica::KinematicTree::octomap_pub_
ros::Publisher octomap_pub_
Definition: kinematic_tree.h:303
exotica::KinematicTree::ResetJointLimits
void ResetJointLimits()
exotica::FIXED
@ FIXED
Definition: kinematic_tree.h:51
exotica::KinematicSolution::start
int start
Definition: kinematic_tree.h:133
exotica::KinematicTree::UpdateJointLimits
void UpdateJointLimits()
exotica::KinematicResponse::frame
std::vector< KinematicFrame > frame
Definition: kinematic_tree.h:118
exotica::LIMIT_POSITION_LOWER
@ LIMIT_POSITION_LOWER
Definition: kinematic_tree.h:66
exotica::ArrayTwist
Eigen::Array< KDL::Twist, Eigen::Dynamic, 1 > ArrayTwist
Definition: conversions.h:152
exotica::KinematicResponse::Phi_dot
ArrayTwist Phi_dot
Definition: kinematic_tree.h:121
exotica::KinematicTree::SetModelState
void SetModelState(Eigen::VectorXdRefConst x)
exotica::KinematicTree::tree_state_
Eigen::VectorXd tree_state_
Definition: kinematic_tree.h:281
exotica::KinematicTree::has_acceleration_limit_
bool has_acceleration_limit_
Definition: kinematic_tree.h:268
kinematic_element.h
exotica::JointLimitType
JointLimitType
Definition: kinematic_tree.h:64
exotica::KinematicResponse::hessian
ArrayHessian hessian
Definition: kinematic_tree.h:123
exotica::KinematicTree::random_state_distributions_
std::vector< std::uniform_real_distribution< double > > random_state_distributions_
Definition: kinematic_tree.h:274
exotica::KinematicTree::GetNumModelJoints
int GetNumModelJoints() const
exotica::KinematicTree::Instantiate
void Instantiate(const std::string &joint_group, robot_model::RobotModelPtr model, const std::string &name)
exotica::KinematicTree::GetRootJointName
const std::string & GetRootJointName() const
exotica::KinematicTree::PublishFrames
void PublishFrames(const std::string &tf_prefix="exotica")
exotica::KinematicTree::GetControlledJoints
const std::vector< std::weak_ptr< KinematicElement > > & GetControlledJoints() const
Definition: kinematic_tree.h:238
exotica::KinematicTree::FK
KDL::Frame FK(KinematicFrame &frame) const
exotica::KinematicTree::SetJointLimitsUpper
void SetJointLimitsUpper(Eigen::VectorXdRefConst upper_in)
exotica::KinematicTree::GetControlledLinkMass
Eigen::VectorXd GetControlledLinkMass() const
exotica::KinematicTree::tree_
std::vector< std::weak_ptr< KinematicElement > > tree_
Definition: kinematic_tree.h:284
exotica::KinematicTree::root_
std::shared_ptr< KinematicElement > root_
Definition: kinematic_tree.h:289
exotica::KinematicFrameRequest::frame_B_link_name
std::string frame_B_link_name
Definition: kinematic_tree.h:89
exotica::KinematicTree::model_
robot_model::RobotModelPtr model_
Definition: kinematic_tree.h:282
exotica::ArrayFrame
Eigen::Array< KDL::Frame, Eigen::Dynamic, 1 > ArrayFrame
Definition: conversions.h:151
exotica::KinematicSolution
The KinematicSolution is created from - and maps into - a KinematicResponse.
Definition: kinematic_tree.h:127
exotica::KinematicTree::joint_limits_
Eigen::MatrixXd joint_limits_
Definition: kinematic_tree.h:265
exotica::KinematicTree::GetCollisionObjectTypes
std::map< std::string, shapes::ShapeType > GetCollisionObjectTypes() const