distance.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020, 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  if (phi.rows() != kinematics[0].Phi.rows()) ThrowNamed("Wrong size of Phi!");
39  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
40  {
41  phi(i) = kinematics[0].Phi(i).p.Norm();
42  }
43 }
44 
46 {
47  if (phi.rows() != kinematics[0].Phi.rows()) ThrowNamed("Wrong size of Phi!");
48  if (jacobian.rows() != kinematics[0].jacobian.rows() || jacobian.cols() != kinematics[0].jacobian(0).data.cols()) ThrowNamed("Wrong size of jacobian! " << kinematics[0].jacobian(0).data.cols());
49  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
50  {
51  phi(i) = kinematics[0].Phi(i).p.Norm();
52  jacobian.row(i) = (kinematics[0].Phi(i).p[0] * kinematics[0].jacobian[i].data.row(0) + kinematics[0].Phi(i).p[1] * kinematics[0].jacobian[i].data.row(1) + kinematics[0].Phi(i).p[2] * kinematics[0].jacobian[i].data.row(2)) / phi(i);
53  }
54 }
55 
57 {
58  if (phi.rows() != kinematics[0].Phi.rows()) ThrowNamed("Wrong size of Phi!");
59  if (jacobian.rows() != kinematics[0].jacobian.rows() || jacobian.cols() != kinematics[0].jacobian(0).data.cols()) ThrowNamed("Wrong size of jacobian! " << kinematics[0].jacobian(0).data.cols());
60  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
61  {
62  const double& p_x = kinematics[0].Phi(i).p[0];
63  const double& p_y = kinematics[0].Phi(i).p[1];
64  const double& p_z = kinematics[0].Phi(i).p[2];
65 
66  const Eigen::RowVectorXd& dp_x_dq = kinematics[0].jacobian[i].data.row(0);
67  const Eigen::RowVectorXd& dp_y_dq = kinematics[0].jacobian[i].data.row(1);
68  const Eigen::RowVectorXd& dp_z_dq = kinematics[0].jacobian[i].data.row(2);
69  Eigen::MatrixXd& ddp_x_ddq = kinematics[0].hessian[i](0);
70  Eigen::MatrixXd& ddp_y_ddq = kinematics[0].hessian[i](1);
71  Eigen::MatrixXd& ddp_z_ddq = kinematics[0].hessian[i](2);
72 
73  phi(i) = kinematics[0].Phi(i).p.Norm();
74  const Eigen::RowVectorXd jacobian_numerator = (kinematics[0].Phi(i).p[0] * kinematics[0].jacobian[i].data.row(0) + kinematics[0].Phi(i).p[1] * kinematics[0].jacobian[i].data.row(1) + kinematics[0].Phi(i).p[2] * kinematics[0].jacobian[i].data.row(2));
75  jacobian.row(i).noalias() = jacobian_numerator / phi(i);
76 
77  // Two part Hessian
78  Eigen::MatrixXd hessian_part1 = -jacobian_numerator.transpose() * jacobian_numerator;
79  hessian_part1 /= std::pow((p_x * p_x + p_y * p_y + p_z * p_z), (3 / 2));
80 
81  Eigen::MatrixXd hessian_part2 = (p_x * ddp_x_ddq + p_y * ddp_y_ddq + p_z * ddp_z_ddq) + (dp_x_dq.transpose() * dp_x_dq + dp_y_dq.transpose() * dp_y_dq + dp_z_dq.transpose() * dp_z_dq);
82  hessian_part2 /= phi(i);
83 
84  hessian(i).noalias() = hessian_part1 + hessian_part2;
85  }
86 }
87 
89 {
90  return kinematics[0].Phi.rows();
91 }
92 
93 } // namespace exotica
Eigen::Ref< Eigen::VectorXd > VectorXdRef
void Update(Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override
Definition: distance.cpp:36
int TaskSpaceDim() override
Definition: distance.cpp:88
#define ThrowNamed(m)
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Eigen::Ref< Hessian > HessianRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
REGISTER_TASKMAP_TYPE("Distance", exotica::Distance)


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09