inverse_kinematics.h
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 #ifndef XPP_VIS_INVERSE_KINEMATICS_H_
31 #define XPP_VIS_INVERSE_KINEMATICS_H_
32 
33 #include <Eigen/Dense>
34 #include <memory>
35 
37 #include <xpp_states/joints.h>
38 
39 namespace xpp {
40 
49 public:
50  using Ptr = std::shared_ptr<InverseKinematics>;
51  using Vector3d = Eigen::Vector3d;
52 
53  InverseKinematics () = default;
54  virtual ~InverseKinematics () = default;
55 
61  virtual Joints GetAllJointAngles(const EndeffectorsPos& pos_b) const = 0;
62 
66  virtual int GetEECount() const = 0;
67 };
68 
69 } /* namespace xpp */
70 
71 #endif /* XPP_VIS_INVERSE_KINEMATICS_H_ */
std::shared_ptr< InverseKinematics > Ptr
virtual int GetEECount() const =0
Number of endeffectors (feet, hands) this implementation expects.
Converts Cartesian endeffector positions into joint angles.
virtual ~InverseKinematics()=default
virtual Joints GetAllJointAngles(const EndeffectorsPos &pos_b) const =0
Calculates the joint angles to reach a position @ pos_b.


xpp_vis
Author(s): Alexander W. Winkler
autogenerated on Tue Dec 8 2020 03:10:32