kinematics-dynamics
Loading...
Searching...
No Matches
KdlTreeSolver.hpp
1// -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2
3#ifndef __KDL_TREE_SOLVER_HPP__
4#define __KDL_TREE_SOLVER_HPP__
5
6#include <map>
7#include <string>
8#include <vector>
9
10#include <yarp/dev/DeviceDriver.h>
11
12#include <kdl/tree.hpp>
13#include <kdl/treefksolver.hpp>
14#include <kdl/treeiksolver.hpp>
15#include <kdl/treeidsolver.hpp>
16
17#include "ICartesianSolver.h"
18#include "KdlTreeSolver_ParamsParser.h"
19
31class KdlTreeSolver : public yarp::dev::DeviceDriver,
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, const std::vector<double> & x_new_old, std::vector<double> & x_new_obj) override;
52
53 // Perform forward kinematics.
54 bool fwdKin(const std::vector<double> & q, std::vector<double> & x) override;
55
56 // Obtain difference between supplied pose inputs.
57 bool poseDiff(const std::vector<double> & xLhs, const std::vector<double> & xRhs, std::vector<double> & xOut) override;
58
59 // Perform inverse kinematics.
60 bool invKin(const std::vector<double> & xd, const std::vector<double> & qGuess, std::vector<double> & q, reference_frame frame) override;
61
62 // Perform differential inverse kinematics.
63 bool diffInvKin(const std::vector<double> & q, const std::vector<double> & xdot, std::vector<double> & qdot, reference_frame frame) override;
64
65 // Perform inverse dynamics.
66 bool invDyn(const std::vector<double> & q, std::vector<double> & t) override;
67
68 // Perform inverse dynamics.
69 bool invDyn(const std::vector<double> & q, const std::vector<double> & qdot, const std::vector<double> & qdotdot,
70 const std::vector<double> & ftip, std::vector<double> & t, reference_frame frame) override;
71
72 // -------- DeviceDriver declarations. Implementation in IDeviceImpl.cpp --------
73
74 bool open(yarp::os::Searchable & config) override;
75
76 bool close() override;
77
78protected:
79 bool makeTree(const yarp::os::Searchable & config);
80
81 std::vector<std::string> endpoints;
82 std::map<std::string, std::string> mergedEndpoints;
83
84 KDL::Tree tree;
85
86 KDL::TreeFkSolverPos * fkSolverPos {nullptr};
87 KDL::TreeIkSolverPos * ikSolverPos {nullptr};
88 KDL::TreeIkSolverVel * ikSolverVel {nullptr};
89 KDL::TreeIdSolver * idSolver {nullptr};
90};
91
92#endif // __KDL_TREE_SOLVER_HPP__
Contains roboticslab::ICartesianSolver.
Definition KdlTreeSolver_ParamsParser.h:54
The KdlTreeSolver class implements ICartesianSolver.
Definition KdlTreeSolver.hpp:34
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 invDyn(const std::vector< double > &q, std::vector< double > &t) override
Perform inverse dynamics.
Definition ICartesianSolverImpl.cpp:262
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:193
bool restoreOriginalChain() override
Restore original kinematic chain.
Definition ICartesianSolverImpl.cpp:42
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:127
int getNumJoints() override
Get number of joints for which the solver has been configured.
Definition ICartesianSolverImpl.cpp:20
bool fwdKin(const std::vector< double > &q, std::vector< double > &x) override
Perform forward kinematics.
Definition ICartesianSolverImpl.cpp:73
bool appendLink(const std::vector< double > &x) override
Append an additional link.
Definition ICartesianSolverImpl.cpp:34
int getNumTcps() override
Get number of TCPs for which the solver has been configured.
Definition ICartesianSolverImpl.cpp:27
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:50
Abstract base class for a cartesian solver.
Definition ICartesianSolver.h:23
reference_frame
Lists supported reference frames.
Definition ICartesianSolver.h:27