state.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #include <vector>
31 
32 #include <xpp_states/state.h>
33 
34 namespace xpp {
35 
36 StateLinXd::StateLinXd (int dim)
37 {
38  kNumDim = dim;
39  p_ = VectorXd::Zero(dim);
40  v_ = VectorXd::Zero(dim);
41  a_ = VectorXd::Zero(dim);
42 }
43 
45  const VectorXd& _v,
46  const VectorXd& _a)
47  :StateLinXd(_p.rows())
48 {
49  p_ = _p;
50  v_ = _v;
51  a_ = _a;
52 }
53 
55  :StateLinXd(_p.rows())
56 {
57  p_ = _p;
58 }
59 
60 const VectorXd
62 {
63  switch (deriv) {
64  case kPos: return p_; break;
65  case kVel: return v_; break;
66  case kAcc: return a_; break;
67  default: throw std::runtime_error("[StateLinXd::GetByIndex] derivative not part of state");
68  }
69 }
70 
73 {
74  switch (deriv) {
75  case kPos: return p_; break;
76  case kVel: return v_; break;
77  case kAcc: return a_; break;
78  default: throw std::runtime_error("[StateLinXd::GetByIndex] derivative not part of state");
79  }
80 }
81 
82 StateLin3d::StateLin3d (const StateLinXd& state_xd) : StateLinXd(3)
83 {
84  assert(state_xd.kNumDim == 3);
85 
86  p_ = state_xd.p_;
87  v_ = state_xd.v_;
88  a_ = state_xd.a_;
89 }
90 
92 StateLin3d::Get2D() const
93 {
94  StateLin2d p2d;
95  p2d.p_ = p_.topRows<kDim2d>();
96  p2d.v_ = v_.topRows<kDim2d>();
97  p2d.a_ = a_.topRows<kDim2d>();
98  return p2d;
99 }
100 
101 Vector6d
102 State3d::Get6dVel () const
103 {
104  Vector6d h_xd;
105  h_xd.segment(AX, 3) = ang.w;
106  h_xd.segment(LX, 3) = lin.v_;
107  return h_xd;
108 }
109 
110 Vector6d
111 State3d::Get6dAcc () const
112 {
113  Vector6d h_xdd;
114  h_xdd.segment(AX, 3) = ang.wd;
115  h_xdd.segment(LX, 3) = lin.a_;
116  return h_xdd;
117 }
118 
119 } // namespace xpp
120 
xpp::StateLinXd::GetByIndex
const VectorXd GetByIndex(MotionDerivative deriv) const
Read either position, velocity of acceleration by index.
Definition: state.cc:88
xpp::kAcc
@ kAcc
Definition: state.h:80
xpp::VectorXd
Eigen::VectorXd VectorXd
Definition: state.h:77
xpp::State3d::lin
StateLin3d lin
linear position, velocity and acceleration
Definition: state.h:203
xpp::StateLinXd::a_
VectorXd a_
position, velocity and acceleration
Definition: state.h:87
xpp::StateLinXd::p_
VectorXd p_
Definition: state.h:87
xpp::MotionDerivative
MotionDerivative
Definition: state.h:80
xpp::StateAng3d::w
Vector3d w
angular velocity (omega).
Definition: state.h:177
xpp::StateLin3d::Get2D
StateLin2d Get2D() const
Extracts only the 2-dimensional part (x,y) from this 3-D state.
Definition: state.cc:119
xpp::State3d::Get6dVel
Vector6d Get6dVel() const
Definition: state.cc:129
xpp::State3d::Get6dAcc
Vector6d Get6dAcc() const
Definition: state.cc:138
xpp::StateLin3d::StateLin3d
StateLin3d()
Definition: state.h:157
xpp::kPos
@ kPos
Definition: state.h:80
xpp::kVel
@ kVel
Definition: state.h:80
xpp::State3d::ang
StateAng3d ang
Quaternion, velocity and acceleration.
Definition: state.h:204
xpp
Definition: cartesian_declarations.h:41
xpp::kDim2d
static constexpr int kDim2d
Definition: cartesian_declarations.h:44
xpp::AX
@ AX
Definition: cartesian_declarations.h:59
xpp::StateLin2d
Definition: state.h:149
xpp::Vector6d
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: state.h:76
xpp::LX
@ LX
Definition: cartesian_declarations.h:59
xpp::StateLinXd
Represents position, velocity and acceleration in x-dimensions.
Definition: state.h:85
xpp::StateLinXd::StateLinXd
StateLinXd(int _dim=0)
Constructs an object of dimensions _dim.
Definition: state.cc:63
state.h
xpp::StateLinXd::v_
VectorXd v_
Definition: state.h:87
xpp::StateAng3d::wd
Vector3d wd
angular acceleration (omega dot).
Definition: state.h:178
xpp::StateLinXd::kNumDim
int kNumDim
the number of dimenions this state represents.
Definition: state.h:137


xpp_states
Author(s): Alexander W. Winkler
autogenerated on Wed Mar 2 2022 01:14:14