eff_frame.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 {
36 void EffFrame::Instantiate(const EffFrameInitializer& init)
37 {
41 }
42 
43 std::vector<TaskVectorEntry> EffFrame::GetLieGroupIndices()
44 {
45  std::vector<TaskVectorEntry> ret;
46  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
47  {
48  ret.push_back(TaskVectorEntry(start + i * big_stride_ + 3, rotation_type_));
49  }
50  return ret;
51 }
52 
54 {
55  if (phi.rows() != kinematics[0].Phi.rows() * big_stride_) ThrowNamed("Wrong size of Phi!");
56  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
57  {
58  phi.segment<3>(i * big_stride_) = Eigen::Map<Eigen::Vector3d>(kinematics[0].Phi(i).p.data);
59  phi.segment(i * big_stride_ + 3, small_stride_) = SetRotation(kinematics[0].Phi(i).M, rotation_type_);
60  }
61 }
62 
64 {
65  if (phi.rows() != kinematics[0].Phi.rows() * big_stride_) ThrowNamed("Wrong size of Phi!");
66  if (jacobian.rows() != kinematics[0].jacobian.rows() * 6 || jacobian.cols() != kinematics[0].jacobian(0).data.cols()) ThrowNamed("Wrong size of jacobian! " << kinematics[0].jacobian(0).data.cols());
67  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
68  {
69  phi.segment<3>(i * big_stride_) = Eigen::Map<Eigen::Vector3d>(kinematics[0].Phi(i).p.data);
70  phi.segment(i * big_stride_ + 3, small_stride_) = SetRotation(kinematics[0].Phi(i).M, rotation_type_);
71  jacobian.middleRows<6>(i * 6) = kinematics[0].jacobian[i].data;
72  }
73 }
74 
76 {
77  if (phi.rows() != kinematics[0].Phi.rows() * big_stride_) ThrowNamed("Wrong size of Phi!");
78  if (jacobian.rows() != kinematics[0].jacobian.rows() * 6 || jacobian.cols() != kinematics[0].jacobian(0).data.cols()) ThrowNamed("Wrong size of jacobian! " << kinematics[0].jacobian(0).data.cols());
79  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
80  {
81  phi.segment<3>(i * big_stride_) = Eigen::Map<Eigen::Vector3d>(kinematics[0].Phi(i).p.data);
82  phi.segment(i * big_stride_ + 3, small_stride_) = SetRotation(kinematics[0].Phi(i).M, rotation_type_);
83  jacobian.middleRows<6>(i * 6) = kinematics[0].jacobian[i].data;
84 
85  for (int j = 0; j < 6; ++j)
86  {
87  hessian(i * 6 + j).block(0, 0, jacobian.cols(), jacobian.cols()) = kinematics[0].hessian[i](j);
88  }
89  }
90 }
91 
93 {
94  return kinematics[0].Phi.rows() * big_stride_;
95 }
96 
98 {
99  return kinematics[0].Phi.rows() * 6;
100 }
101 
103 {
104  return rotation_type_;
105 }
106 
107 } // namespace exotica
const RotationType & get_rotation_type() const
Definition: eff_frame.cpp:102
Eigen::Ref< Eigen::VectorXd > VectorXdRef
RotationType GetRotationTypeFromString(const std::string &rotation_type)
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
Definition: eff_frame.cpp:53
#define ThrowNamed(m)
RotationType rotation_type_
Definition: eff_frame.h:57
void Instantiate(const EffFrameInitializer &init) override
Definition: eff_frame.cpp:36
std::vector< TaskVectorEntry > GetLieGroupIndices() override
Definition: eff_frame.cpp:43
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Eigen::VectorXd SetRotation(const KDL::Rotation &data, RotationType type)
REGISTER_TASKMAP_TYPE("EffFrame", exotica::EffFrame)
int GetRotationTypeLength(const RotationType &type)
Eigen::Ref< Hessian > HessianRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
int TaskSpaceDim() override
Definition: eff_frame.cpp:92
int TaskSpaceJacobianDim() override
Definition: eff_frame.cpp:97


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