kinematic_element.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_ELEMENT_H_
31 #define EXOTICA_CORE_KINEMATIC_ELEMENT_H_
32 
33 #include <exotica_core/tools.h>
35 #include <kdl/frames.hpp>
36 #include <kdl/segment.hpp>
37 #include <stack>
38 
39 namespace exotica
40 {
42 {
43 public:
44  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
45 
46  std::string name;
48  std::string shape_resource_path = "";
49  KDL::Frame frame = KDL::Frame::Identity();
50  Eigen::Vector3d scale = Eigen::Vector3d::Ones();
51  Eigen::Vector4d color = Eigen::Vector4d(1.0, 1.0, 1.0, 1.0);
52 };
53 
55 {
56 public:
57  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
58 
59  KinematicElement(int _id, std::shared_ptr<KinematicElement> _parent, const KDL::Segment& _segment) : id(_id), parent(_parent), segment(_segment)
60  {
61  if (_parent)
62  {
63  parent_name = _parent->segment.getName();
64  }
65  }
66 
68  {
69  // Remove from parent to avoid expired pointers
70  std::shared_ptr<KinematicElement> my_parent = parent.lock();
71  if (my_parent)
72  {
73  my_parent->RemoveExpiredChildren();
74  }
75  }
76 
77  inline void UpdateClosestRobotLink()
78  {
79  std::shared_ptr<KinematicElement> element = parent.lock();
80  closest_robot_link = std::shared_ptr<KinematicElement>(nullptr);
81  while (element && element->id > 0)
82  {
83  if (element->is_robot_link)
84  {
85  closest_robot_link = element;
86  break;
87  }
88  element = element->parent.lock();
89  }
91  }
92 
93  inline KDL::Frame GetPose(const double& x = 0.0)
94  {
96  {
97  return generated_offset;
98  }
99  else if (is_mimic_joint)
100  {
101  return segment.pose(mimic_offset + mimic_multiplier * x);
102  }
103  else
104  {
105  return segment.pose(x);
106  }
107  }
108 
109  inline void RemoveExpiredChildren()
110  {
111  for (size_t i = 0; i < children.size(); ++i)
112  {
113  if (children[i].expired())
114  {
115  children.erase(children.begin() + i);
116  }
117  }
118  }
119 
120  int id;
121  int control_id = -1;
122  bool is_controlled = false;
123  std::weak_ptr<KinematicElement> parent;
124  std::string parent_name;
125  std::vector<std::weak_ptr<KinematicElement>> children;
126  std::weak_ptr<KinematicElement> closest_robot_link = std::shared_ptr<KinematicElement>(nullptr);
127  KDL::Segment segment = KDL::Segment();
128  KDL::Frame frame = KDL::Frame::Identity();
129  KDL::Frame generated_offset = KDL::Frame::Identity();
131  bool is_mimic_joint = false;
132  int mimic_joint_id = -1; // ID of the joint to mimic
133  double mimic_multiplier = 1.0;
134  double mimic_offset = 0.0;
135  std::vector<double> joint_limits;
136  double velocity_limit = std::numeric_limits<double>::quiet_NaN();
137  double acceleration_limit = std::numeric_limits<double>::quiet_NaN();
139  std::string shape_resource_path = std::string();
140  Eigen::Vector3d scale = Eigen::Vector3d::Ones();
141  bool is_robot_link = false;
142  Eigen::Vector4d color = Eigen::Vector4d(0.5, 0.5, 0.5, 1.0);
143  std::vector<VisualElement> visual;
144 
145 private:
147  {
148  std::stack<std::shared_ptr<KinematicElement>> elements;
149  for (auto child : children) elements.push(child.lock());
150  while (!elements.empty())
151  {
152  auto parent = elements.top();
153  elements.pop();
154  parent->closest_robot_link = closest_robot_link;
155  for (auto child : parent->children) elements.push(child.lock());
156  }
157  }
158 };
159 } // namespace exotica
160 
161 #endif // EXOTICA_CORE_KINEMATIC_ELEMENT_H_
exotica::KinematicElement::KinematicElement
EIGEN_MAKE_ALIGNED_OPERATOR_NEW KinematicElement(int _id, std::shared_ptr< KinematicElement > _parent, const KDL::Segment &_segment)
Definition: kinematic_element.h:59
exotica::KinematicElement::mimic_offset
double mimic_offset
Definition: kinematic_element.h:134
exotica::KinematicElement::~KinematicElement
~KinematicElement()
Definition: kinematic_element.h:67
exotica::KinematicElement::is_trajectory_generated
bool is_trajectory_generated
Definition: kinematic_element.h:130
exotica::KinematicElement::shape_resource_path
std::string shape_resource_path
Definition: kinematic_element.h:139
exotica::VisualElement::name
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string name
Definition: kinematic_element.h:46
exotica::KinematicElement::is_controlled
bool is_controlled
Definition: kinematic_element.h:122
exotica::KinematicElement::velocity_limit
double velocity_limit
Definition: kinematic_element.h:136
exotica::KinematicElement::color
Eigen::Vector4d color
Definition: kinematic_element.h:142
exotica::KinematicElement::SetChildrenClosestRobotLink
void SetChildrenClosestRobotLink()
Definition: kinematic_element.h:146
exotica::KinematicElement::closest_robot_link
std::weak_ptr< KinematicElement > closest_robot_link
Definition: kinematic_element.h:126
exotica::KinematicElement::parent
std::weak_ptr< KinematicElement > parent
Definition: kinematic_element.h:123
exotica::KinematicElement::parent_name
std::string parent_name
Definition: kinematic_element.h:124
exotica
Definition: collision_scene.h:46
exotica::KinematicElement::generated_offset
KDL::Frame generated_offset
Definition: kinematic_element.h:129
exotica::VisualElement::shape_resource_path
std::string shape_resource_path
Definition: kinematic_element.h:48
exotica::KinematicElement::joint_limits
std::vector< double > joint_limits
Definition: kinematic_element.h:135
exotica::KinematicElement::visual
std::vector< VisualElement > visual
Definition: kinematic_element.h:143
shapes::ShapePtr
std::shared_ptr< Shape > ShapePtr
exotica::KinematicElement
Definition: kinematic_element.h:54
exotica::KinematicElement::mimic_multiplier
double mimic_multiplier
Definition: kinematic_element.h:133
exotica::KinematicElement::is_mimic_joint
bool is_mimic_joint
Definition: kinematic_element.h:131
shapes.h
exotica::VisualElement::scale
Eigen::Vector3d scale
Definition: kinematic_element.h:50
exotica::KinematicElement::UpdateClosestRobotLink
void UpdateClosestRobotLink()
Definition: kinematic_element.h:77
exotica::KinematicElement::mimic_joint_id
int mimic_joint_id
Definition: kinematic_element.h:132
exotica::VisualElement
Definition: kinematic_element.h:41
exotica::KinematicElement::RemoveExpiredChildren
void RemoveExpiredChildren()
Definition: kinematic_element.h:109
exotica::KinematicElement::segment
KDL::Segment segment
Definition: kinematic_element.h:127
exotica::KinematicElement::control_id
int control_id
Definition: kinematic_element.h:121
exotica::KinematicElement::frame
KDL::Frame frame
Definition: kinematic_element.h:128
exotica::KinematicElement::shape
shapes::ShapeConstPtr shape
Definition: kinematic_element.h:138
exotica::KinematicElement::children
std::vector< std::weak_ptr< KinematicElement > > children
Definition: kinematic_element.h:125
exotica::KinematicElement::is_robot_link
bool is_robot_link
Definition: kinematic_element.h:141
exotica::VisualElement::frame
KDL::Frame frame
Definition: kinematic_element.h:49
exotica::KinematicElement::id
int id
Definition: kinematic_element.h:120
exotica::KinematicElement::scale
Eigen::Vector3d scale
Definition: kinematic_element.h:140
exotica::KinematicElement::acceleration_limit
double acceleration_limit
Definition: kinematic_element.h:137
exotica::VisualElement::shape
shapes::ShapePtr shape
Definition: kinematic_element.h:47
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
x
double x
tools.h
exotica::KinematicElement::GetPose
KDL::Frame GetPose(const double &x=0.0)
Definition: kinematic_element.h:93
exotica::VisualElement::color
Eigen::Vector4d color
Definition: kinematic_element.h:51


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sun Jun 2 2024 02:58:18