00001 /****************************************************************************** 00002 Copyright (c) 2017, Alexander W. Winkler. All rights reserved. 00003 00004 Redistribution and use in source and binary forms, with or without 00005 modification, are permitted provided that the following conditions are met: 00006 00007 * Redistributions of source code must retain the above copyright notice, this 00008 list of conditions and the following disclaimer. 00009 00010 * Redistributions in binary form must reproduce the above copyright notice, 00011 this list of conditions and the following disclaimer in the documentation 00012 and/or other materials provided with the distribution. 00013 00014 * Neither the name of the copyright holder nor the names of its 00015 contributors may be used to endorse or promote products derived from 00016 this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00028 ******************************************************************************/ 00029 00030 #include <vector> 00031 00032 #include <xpp_states/state.h> 00033 00034 namespace xpp { 00035 00036 StateLinXd::StateLinXd (int dim) 00037 { 00038 kNumDim = dim; 00039 p_ = VectorXd::Zero(dim); 00040 v_ = VectorXd::Zero(dim); 00041 a_ = VectorXd::Zero(dim); 00042 } 00043 00044 StateLinXd::StateLinXd (const VectorXd& _p, 00045 const VectorXd& _v, 00046 const VectorXd& _a) 00047 :StateLinXd(_p.rows()) 00048 { 00049 p_ = _p; 00050 v_ = _v; 00051 a_ = _a; 00052 } 00053 00054 StateLinXd::StateLinXd (const VectorXd& _p) 00055 :StateLinXd(_p.rows()) 00056 { 00057 p_ = _p; 00058 } 00059 00060 const VectorXd 00061 StateLinXd::GetByIndex (MotionDerivative deriv) const 00062 { 00063 switch (deriv) { 00064 case kPos: return p_; break; 00065 case kVel: return v_; break; 00066 case kAcc: return a_; break; 00067 default: assert(false); // derivative not part of state 00068 } 00069 } 00070 00071 VectorXd& 00072 StateLinXd::GetByIndex (MotionDerivative deriv) 00073 { 00074 switch (deriv) { 00075 case kPos: return p_; break; 00076 case kVel: return v_; break; 00077 case kAcc: return a_; break; 00078 default: assert(false); // derivative not part of state 00079 } 00080 } 00081 00082 StateLin3d::StateLin3d (const StateLinXd& state_xd) : StateLinXd(3) 00083 { 00084 assert(state_xd.kNumDim == 3); 00085 00086 p_ = state_xd.p_; 00087 v_ = state_xd.v_; 00088 a_ = state_xd.a_; 00089 } 00090 00091 StateLin2d 00092 StateLin3d::Get2D() const 00093 { 00094 StateLin2d p2d; 00095 p2d.p_ = p_.topRows<kDim2d>(); 00096 p2d.v_ = v_.topRows<kDim2d>(); 00097 p2d.a_ = a_.topRows<kDim2d>(); 00098 return p2d; 00099 } 00100 00101 Vector6d 00102 State3d::Get6dVel () const 00103 { 00104 Vector6d h_xd; 00105 h_xd.segment(AX, 3) = ang.w; 00106 h_xd.segment(LX, 3) = lin.v_; 00107 return h_xd; 00108 } 00109 00110 Vector6d 00111 State3d::Get6dAcc () const 00112 { 00113 Vector6d h_xdd; 00114 h_xdd.segment(AX, 3) = ang.wd; 00115 h_xdd.segment(LX, 3) = lin.a_; 00116 return h_xdd; 00117 } 00118 00119 } // namespace xpp 00120