kinematics-dynamics
ICartesianSolver.h
Go to the documentation of this file.
1 // -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2 
3 #ifndef __I_CARTESIAN_SOLVER__
4 #define __I_CARTESIAN_SOLVER__
5 
6 #include <vector>
7 #include <yarp/os/Vocab.h>
8 
16 namespace roboticslab
17 {
18 
23 {
24 public:
27  {
28  BASE_FRAME = yarp::os::createVocab32('c','p','f','b'),
29  TCP_FRAME = yarp::os::createVocab32('c','p','f','t')
30  };
31 
33  virtual ~ICartesianSolver() = default;
34 
40  virtual int getNumJoints() = 0;
41 
47  virtual int getNumTcps() = 0;
48 
58  virtual bool appendLink(const std::vector<double>& x) = 0;
59 
65  virtual bool restoreOriginalChain() = 0;
66 
82  virtual bool changeOrigin(const std::vector<double> &x_old_obj,
83  const std::vector<double> &x_new_old,
84  std::vector<double> &x_new_obj) = 0;
85 
96  virtual bool fwdKin(const std::vector<double> &q, std::vector<double> &x) = 0;
97 
116  virtual bool poseDiff(const std::vector<double> &xLhs, const std::vector<double> &xRhs, std::vector<double> &xOut) = 0;
117 
130  virtual bool invKin(const std::vector<double> &xd, const std::vector<double> &qGuess, std::vector<double> &q,
131  reference_frame frame = BASE_FRAME) = 0;
132 
145  virtual bool diffInvKin(const std::vector<double> &q, const std::vector<double> &xdot, std::vector<double> &qdot,
146  reference_frame frame = BASE_FRAME) = 0;
147 
160  virtual bool invDyn(const std::vector<double> &q, std::vector<double> &t) = 0;
161 
162 #ifndef SWIG_PREPROCESSOR_SHOULD_SKIP_THIS
178  [[deprecated("use `const std::vector<double> &ftip` signature instead")]]
179  virtual bool invDyn(const std::vector<double> &q, const std::vector<double> &qdot, const std::vector<double> &qdotdot,
180  const std::vector<std::vector<double>> &fexts, std::vector<double> &t)
181  {
182  return invDyn(q, qdot, qdotdot, fexts.back(), t);
183  }
184 #endif
185 
202  virtual bool invDyn(const std::vector<double> &q, const std::vector<double> &qdot, const std::vector<double> &qdotdot,
203  const std::vector<double> &ftip, std::vector<double> &t, reference_frame frame = BASE_FRAME) = 0;
204 };
205 
206 } // namespace roboticslab
207 
210 #endif // __I_CARTESIAN_SOLVER__
Abstract base class for a cartesian solver.
Definition: ICartesianSolver.h:23
virtual int getNumTcps()=0
Get number of TCPs for which the solver has been configured.
virtual bool appendLink(const std::vector< double > &x)=0
Append an additional link.
virtual bool invDyn(const std::vector< double > &q, const std::vector< double > &qdot, const std::vector< double > &qdotdot, const std::vector< double > &ftip, std::vector< double > &t, reference_frame frame=BASE_FRAME)=0
Perform inverse dynamics.
virtual bool fwdKin(const std::vector< double > &q, std::vector< double > &x)=0
Perform forward kinematics.
virtual bool restoreOriginalChain()=0
Restore original kinematic chain.
virtual bool invKin(const std::vector< double > &xd, const std::vector< double > &qGuess, std::vector< double > &q, reference_frame frame=BASE_FRAME)=0
Perform inverse kinematics.
virtual bool changeOrigin(const std::vector< double > &x_old_obj, const std::vector< double > &x_new_old, std::vector< double > &x_new_obj)=0
Change origin in which a pose is expressed.
virtual ~ICartesianSolver()=default
Destructor.
virtual bool diffInvKin(const std::vector< double > &q, const std::vector< double > &xdot, std::vector< double > &qdot, reference_frame frame=BASE_FRAME)=0
Perform differential inverse kinematics.
virtual bool invDyn(const std::vector< double > &q, const std::vector< double > &qdot, const std::vector< double > &qdotdot, const std::vector< std::vector< double >> &fexts, std::vector< double > &t)
Perform inverse dynamics.
Definition: ICartesianSolver.h:179
virtual int getNumJoints()=0
Get number of joints for which the solver has been configured.
reference_frame
Lists supported reference frames.
Definition: ICartesianSolver.h:27
@ TCP_FRAME
End-effector frame (TCP)
Definition: ICartesianSolver.h:29
@ BASE_FRAME
Base frame.
Definition: ICartesianSolver.h:28
virtual bool poseDiff(const std::vector< double > &xLhs, const std::vector< double > &xRhs, std::vector< double > &xOut)=0
Obtain difference between supplied pose inputs.
virtual bool invDyn(const std::vector< double > &q, std::vector< double > &t)=0
Perform inverse dynamics.
The main, catch-all namespace for Robotics Lab UC3M.
Definition: groups.dox:6