joint_limit.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2023, University of Edinburgh, University of Oxford
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 
31 
33 
34 namespace exotica
35 {
37 {
38  scene_ = scene;
39  Initialize();
40 }
41 
43 {
44  safe_percentage_ = parameters_.SafePercentage;
45 
46  if (scene_->get_num_velocities() > 0)
47  {
48  // Position and velocity joint limits
49  N = scene_->get_num_state_derivative();
50  }
51  else
52  {
53  // Kinematic joint limits
54  N = scene_->GetKinematicTree().GetNumControlledJoints();
55  }
56 }
57 
59 {
60  return N;
61 }
62 
64 {
65  if (phi.rows() != N) ThrowNamed("Wrong size of phi!");
66 
67  const Eigen::MatrixXd& limits = scene_->GetKinematicTree().GetJointLimits();
68  const Eigen::VectorXd& low_limits = limits.col(0);
69  const Eigen::VectorXd& high_limits = limits.col(1);
70  const Eigen::VectorXd tau = 0.5 * safe_percentage_ * (high_limits - low_limits);
71 
72  // apply lower bounds
73  phi = (q.array() < (low_limits + tau).array()).select(q - low_limits - tau, phi);
74  // apply higher bounds
75  phi = (q.array() > (high_limits - tau).array()).select(q - high_limits + tau, phi);
76 }
77 
79 {
80  if (jacobian.rows() != N || jacobian.cols() != N) ThrowNamed("Wrong size of jacobian! " << N);
81  Update(q, phi);
82 
83  // The jacobian is piece-wise: It's 0 when within limits, and 1 when outside.
84  const Eigen::MatrixXd& limits = scene_->GetKinematicTree().GetJointLimits();
85  const Eigen::VectorXd& low_limits = limits.col(0);
86  const Eigen::VectorXd& high_limits = limits.col(1);
87  const Eigen::VectorXd tau = 0.5 * safe_percentage_ * (high_limits - low_limits);
88  for (int i = 0; i < N; i++)
89  {
90  if (q(i) >= low_limits(i) + tau(i) && q(i) <= high_limits(i) - tau(i))
91  {
92  jacobian(i, i) = 0;
93  }
94  else
95  {
96  jacobian(i, i) = 1;
97  }
98  }
99 }
100 
102 {
103  if (hessian.size() != N) ThrowNamed("Wrong size of hessian! " << N);
104  // Hessian is 0.
105  Update(x, phi, jacobian);
106 }
107 
109 {
110  if (phi.rows() != N) ThrowNamed("Wrong size of phi!");
111 
112  // Build limits vector for state limits:
113  Eigen::VectorXd low_limits(N), high_limits(N);
114 
115  const Eigen::MatrixXd& limits = scene_->GetKinematicTree().GetJointLimits();
116  low_limits.head(scene_->get_num_positions()) = limits.col(0);
117  high_limits.head(scene_->get_num_positions()) = limits.col(1);
118 
119  low_limits.tail(scene_->get_num_velocities()) = -scene_->GetKinematicTree().GetVelocityLimits();
120  high_limits.tail(scene_->get_num_velocities()) = scene_->GetKinematicTree().GetVelocityLimits();
121 
122  const Eigen::VectorXd tau = 0.5 * safe_percentage_ * (high_limits - low_limits);
123 
124  // apply lower bounds
125  phi = (x.array() < (low_limits + tau).array()).select(x - low_limits - tau, phi);
126  // apply higher bounds
127  phi = (x.array() > (high_limits - tau).array()).select(x - high_limits + tau, phi);
128 }
129 
131 {
132  if (dphi_dx.rows() != N || dphi_dx.cols() != N) ThrowNamed("Wrong size of dphi_dx! " << N);
133  if (phi.rows() != N) ThrowNamed("Wrong size of phi!");
134 
135  // Build limits vector for state limits:
136  Eigen::VectorXd low_limits(N), high_limits(N);
137 
138  const Eigen::MatrixXd& limits = scene_->GetKinematicTree().GetJointLimits();
139  low_limits.head(scene_->get_num_positions()) = limits.col(0);
140  high_limits.head(scene_->get_num_positions()) = limits.col(1);
141 
142  low_limits.tail(scene_->get_num_velocities()) = -scene_->GetKinematicTree().GetVelocityLimits();
143  high_limits.tail(scene_->get_num_velocities()) = scene_->GetKinematicTree().GetVelocityLimits();
144 
145  const Eigen::VectorXd tau = 0.5 * safe_percentage_ * (high_limits - low_limits);
146 
147  // apply lower bounds
148  phi = (x.array() < (low_limits + tau).array()).select(x - low_limits - tau, phi);
149  // apply higher bounds
150  phi = (x.array() > (high_limits - tau).array()).select(x - high_limits + tau, phi);
151 
152  for (int i = 0; i < N; i++)
153  {
154  if (x(i) >= low_limits(i) + tau(i) && x(i) <= high_limits(i) - tau(i))
155  {
156  dphi_dx(i, i) = 0;
157  }
158  else
159  {
160  dphi_dx(i, i) = 1;
161  }
162  }
163 }
164 
166 {
167  // Hessian is 0.
168  Update(x, u, phi, dphi_dx, dphi_du);
169 }
170 
171 } // namespace exotica
exotica::Instantiable< JointLimitInitializer >::parameters_
C parameters_
exotica::JointLimit
Implementation of joint limits task map. Note: we dont want to always stay at the centre of the joint...
Definition: joint_limit.h:42
select
size_t select(const BV &query, const NodeBase< BV > &node1, const NodeBase< BV > &node2)
joint_limit.h
exotica::JointLimit::AssignScene
void AssignScene(ScenePtr scene) override
Definition: joint_limit.cpp:36
REGISTER_TASKMAP_TYPE
REGISTER_TASKMAP_TYPE("JointLimit", exotica::JointLimit)
exotica::JointLimit::Initialize
void Initialize()
Definition: joint_limit.cpp:42
exotica
exotica::JointLimit::TaskSpaceDim
int TaskSpaceDim() override
Definition: joint_limit.cpp:58
exotica::ScenePtr
std::shared_ptr< Scene > ScenePtr
Eigen::VectorXdRef
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
exotica::TaskMap::scene_
ScenePtr scene_
Eigen::MatrixXdRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
exotica::HessianRef
Eigen::Ref< Hessian > HessianRef
exotica::JointLimit::N
int N
Definition: joint_limit.h:61
exotica::JointLimit::Update
void Update(Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override
Definition: joint_limit.cpp:63
x
double x
exotica::JointLimit::safe_percentage_
double safe_percentage_
Definition: joint_limit.h:60
ThrowNamed
#define ThrowNamed(m)


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:44:10