3#ifndef __KDL_TREE_SOLVER_HPP__
4#define __KDL_TREE_SOLVER_HPP__
10#include <yarp/dev/DeviceDriver.h>
12#include <kdl/tree.hpp>
13#include <kdl/treefksolver.hpp>
14#include <kdl/treeiksolver.hpp>
15#include <kdl/treeidsolver.hpp>
18#include "KdlTreeSolver_ParamsParser.h"
45 bool appendLink(
const std::vector<double> & x)
override;
51 bool changeOrigin(
const std::vector<double> & x_old_obj,
const std::vector<double> & x_new_old, std::vector<double> & x_new_obj)
override;
54 bool fwdKin(
const std::vector<double> & q, std::vector<double> & x)
override;
57 bool poseDiff(
const std::vector<double> & xLhs,
const std::vector<double> & xRhs, std::vector<double> & xOut)
override;
60 bool invKin(
const std::vector<double> & xd,
const std::vector<double> & qGuess, std::vector<double> & q,
reference_frame frame)
override;
63 bool diffInvKin(
const std::vector<double> & q,
const std::vector<double> & xdot, std::vector<double> & qdot,
reference_frame frame)
override;
66 bool invDyn(
const std::vector<double> & q, std::vector<double> & t)
override;
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;
74 bool open(yarp::os::Searchable & config)
override;
76 bool close()
override;
79 bool makeTree(
const yarp::os::Searchable & config);
81 std::vector<std::string> endpoints;
82 std::map<std::string, std::string> mergedEndpoints;
86 KDL::TreeFkSolverPos * fkSolverPos {
nullptr};
87 KDL::TreeIkSolverPos * ikSolverPos {
nullptr};
88 KDL::TreeIkSolverVel * ikSolverVel {
nullptr};
89 KDL::TreeIdSolver * idSolver {
nullptr};
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