kinematics-dynamics
Loading...
Searching...
No Matches
KdlSolver.hpp
1// -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2
3#ifndef __KDL_SOLVER_HPP__
4#define __KDL_SOLVER_HPP__
5
6#include <mutex>
7
8#include <yarp/dev/DeviceDriver.h>
9
10#include <kdl/chain.hpp>
11#include <kdl/chainfksolver.hpp>
12#include <kdl/chainiksolver.hpp>
13#include <kdl/chainidsolver.hpp>
14
15#include "ICartesianSolver.h"
16#include "LogComponent.hpp"
17
18namespace roboticslab
19{
20
32class KdlSolver : public yarp::dev::DeviceDriver,
33 public ICartesianSolver
34{
35public:
36 // -- ICartesianSolver declarations. Implementation in ICartesianSolverImpl.cpp--
37
38 // Get number of joints for which the solver has been configured.
39 int getNumJoints() override;
40
41 // Get number of TCPs for which the solver has been configured.
42 int getNumTcps() override;
43
44 // Append an additional link.
45 bool appendLink(const std::vector<double>& x) override;
46
47 // Restore original kinematic chain.
48 bool restoreOriginalChain() override;
49
50 // Change reference frame.
51 bool changeOrigin(const std::vector<double> &x_old_obj,
52 const std::vector<double> &x_new_old,
53 std::vector<double> &x_new_obj) override;
54
55 // Perform forward kinematics.
56 bool fwdKin(const std::vector<double> &q, std::vector<double> &x) override;
57
58 // Obtain difference between supplied pose inputs.
59 bool poseDiff(const std::vector<double> &xLhs, const std::vector<double> &xRhs, std::vector<double> &xOut) override;
60
61 // Perform inverse kinematics.
62 bool invKin(const std::vector<double> &xd, const std::vector<double> &qGuess, std::vector<double> &q,
63 reference_frame frame) override;
64
65 // Perform differential inverse kinematics.
66 bool diffInvKin(const std::vector<double> &q, const std::vector<double> &xdot, std::vector<double> &qdot,
67 reference_frame frame) override;
68
69 // Perform inverse dynamics.
70 bool invDyn(const std::vector<double> &q, std::vector<double> &t) override;
71
72 // Perform inverse dynamics.
73 bool invDyn(const std::vector<double> &q, const std::vector<double> &qdot, const std::vector<double> &qdotdot,
74 const std::vector<double> &ftip, std::vector<double> &t, reference_frame frame) override;
75
76 // -------- DeviceDriver declarations. Implementation in IDeviceImpl.cpp --------
77
78 bool open(yarp::os::Searchable & config) override;
79 bool close() override;
80
81private:
82 inline const yarp::os::LogComponent & logc() const
83 { return !isQuiet ? KDLS() : KDLS_QUIET(); }
84
85 mutable std::mutex mtx;
86
88 KDL::Chain chain;
89
91 KDL::Chain originalChain;
92
93 KDL::ChainFkSolverPos * fkSolverPos {nullptr};
94 KDL::ChainIkSolverPos * ikSolverPos {nullptr};
95 KDL::ChainIkSolverVel * ikSolverVel {nullptr};
96 KDL::ChainIdSolver * idSolver {nullptr};
97
98 bool isQuiet;
99};
100
101} // namespace roboticslab
102
103#endif // __KDL_SOLVER_HPP__
Contains roboticslab::ICartesianSolver.
Abstract base class for a cartesian solver.
Definition ICartesianSolver.h:23
reference_frame
Lists supported reference frames.
Definition ICartesianSolver.h:27
The KdlSolver class implements ICartesianSolver.
Definition KdlSolver.hpp:34
bool restoreOriginalChain() override
Restore original kinematic chain.
Definition ICartesianSolverImpl.cpp:51
bool invDyn(const std::vector< double > &q, std::vector< double > &t) override
Perform inverse dynamics.
Definition ICartesianSolverImpl.cpp:225
bool poseDiff(const std::vector< double > &xLhs, const std::vector< double > &xRhs, std::vector< double > &xOut) override
Obtain difference between supplied pose inputs.
Definition ICartesianSolverImpl.cpp:103
bool invKin(const std::vector< double > &xd, const std::vector< double > &qGuess, std::vector< double > &q, reference_frame frame) override
Perform inverse kinematics.
Definition ICartesianSolverImpl.cpp:116
bool changeOrigin(const std::vector< double > &x_old_obj, const std::vector< double > &x_new_old, std::vector< double > &x_new_obj) override
Change origin in which a pose is expressed.
Definition ICartesianSolverImpl.cpp:67
KDL::Chain chain
Definition KdlSolver.hpp:88
int getNumJoints() override
Get number of joints for which the solver has been configured.
Definition ICartesianSolverImpl.cpp:19
int getNumTcps() override
Get number of TCPs for which the solver has been configured.
Definition ICartesianSolverImpl.cpp:26
bool diffInvKin(const std::vector< double > &q, const std::vector< double > &xdot, std::vector< double > &qdot, reference_frame frame) override
Perform differential inverse kinematics.
Definition ICartesianSolverImpl.cpp:169
bool fwdKin(const std::vector< double > &q, std::vector< double > &x) override
Perform forward kinematics.
Definition ICartesianSolverImpl.cpp:80
KDL::Chain originalChain
Definition KdlSolver.hpp:91
bool appendLink(const std::vector< double > &x) override
Append an additional link.
Definition ICartesianSolverImpl.cpp:33
The main, catch-all namespace for Robotics Lab UC3M.
Definition groups.dox:6