kinematics-dynamics
ChainFkSolverPos_ST.hpp
1 // -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2 
3 #ifndef __CHAIN_FK_SOLVER_POS_ST_HPP__
4 #define __CHAIN_FK_SOLVER_POS_ST_HPP__
5 
6 #include <kdl/chainfksolver.hpp>
7 
8 #include "ProductOfExponentials.hpp"
9 
10 namespace roboticslab
11 {
12 
21 class ChainFkSolverPos_ST : public KDL::ChainFkSolverPos
22 {
23 public:
33  int JntToCart(const KDL::JntArray & q_in, KDL::Frame & p_out, int segmentNr = -1) override;
34 
46  int JntToCart(const KDL::JntArray & q_in, std::vector<KDL::Frame> & p_out, int segmentNr = -1) override;
47 
55  void updateInternalDataStructures() override;
56 
65  const char * strError(const int error) const override;
66 
74  static KDL::ChainFkSolverPos * create(const KDL::Chain & chain);
75 
77  static const int E_OPERATION_NOT_SUPPORTED = -100;
78 
80  static const int E_ILLEGAL_ARGUMENT_SIZE = -101;
81 
82 private:
83  ChainFkSolverPos_ST(const KDL::Chain & chain);
84 
85  const KDL::Chain & chain;
86 
87  PoeExpression poe;
88 };
89 
90 } // namespace roboticslab
91 
92 #endif // __CHAIN_FK_SOLVER_POS_ST_HPP__
FK solver using Screw Theory.
Definition: ChainFkSolverPos_ST.hpp:22
void updateInternalDataStructures() override
Update the internal data structures.
Definition: ChainFkSolverPos_ST.cpp:40
static const int E_ILLEGAL_ARGUMENT_SIZE
Return code, input vector size does not match expected output vector size.
Definition: ChainFkSolverPos_ST.hpp:80
static const int E_OPERATION_NOT_SUPPORTED
Return code, operation not supported.
Definition: ChainFkSolverPos_ST.hpp:77
static KDL::ChainFkSolverPos * create(const KDL::Chain &chain)
Create an instance of ChainFkSolverPos_ST.
Definition: ChainFkSolverPos_ST.cpp:62
const char * strError(const int error) const override
Return a description of the last error.
Definition: ChainFkSolverPos_ST.cpp:47
int JntToCart(const KDL::JntArray &q_in, KDL::Frame &p_out, int segmentNr=-1) override
Perform FK on the selected segment.
Definition: ChainFkSolverPos_ST.cpp:16
Abstraction of a product of exponentials (POE) formula.
Definition: ProductOfExponentials.hpp:28
The main, catch-all namespace for Robotics Lab UC3M.
Definition: groups.dox:6