kinematics-dynamics
Loading...
Searching...
No Matches
AsibotSolver.hpp
1// -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2
3#ifndef __ASIBOT_SOLVER_HPP__
4#define __ASIBOT_SOLVER_HPP__
5
6#include <mutex>
7
8#include <yarp/os/Searchable.h>
9#include <yarp/dev/DeviceDriver.h>
10#include <yarp/sig/Matrix.h>
11
12#include "AsibotConfiguration.hpp"
13#include "ICartesianSolver.h"
14#include "AsibotSolver_ParamsParser.h"
15
27class AsibotSolver : public yarp::dev::DeviceDriver,
30{
31public:
32 // -------- ICartesianSolver declarations. Implementation in ICartesianSolverImpl.cpp --------
33
34 // Get number of joints for which the solver has been configured.
35 int getNumJoints() override;
36
37 // Get number of TCPs for which the solver has been configured.
38 int getNumTcps() override;
39
40 // Append an additional link.
41 bool appendLink(const std::vector<double> &x) override;
42
43 // Restore original kinematic chain.
44 bool restoreOriginalChain() override;
45
46 // Change reference frame.
47 bool changeOrigin(const std::vector<double> &x_old_obj, const std::vector<double> &x_new_old, std::vector<double> &x_new_obj) override;
48
49 // Perform forward kinematics.
50 bool fwdKin(const std::vector<double> &q, std::vector<double> &x) override;
51
52 // Obtain difference between supplied pose inputs.
53 bool poseDiff(const std::vector<double> &xLhs, const std::vector<double> &xRhs, std::vector<double> &xOut) override;
54
55 // Perform inverse kinematics.
56 bool invKin(const std::vector<double> &xd, const std::vector<double> &qGuess, std::vector<double> &q, reference_frame frame) override;
57
58 // Perform differential inverse kinematics.
59 bool diffInvKin(const std::vector<double> &q, const std::vector<double> &xdot, std::vector<double> &qdot, reference_frame frame) override;
60
61 // Perform inverse dynamics.
62 bool invDyn(const std::vector<double> &q, std::vector<double> &t) override;
63
64 // Perform inverse dynamics.
65 bool invDyn(const std::vector<double> &q, const std::vector<double> &qdot, const std::vector<double> &qdotdot,
66 const std::vector<double> &ftip, std::vector<double> &t, reference_frame frame) override;
67
68 // -------- DeviceDriver declarations. Implementation in DeviceDriverImpl.cpp --------
69 bool open(yarp::os::Searchable& config) override;
70 bool close() override;
71
72private:
74 {
75 bool hasFrame;
76 yarp::sig::Matrix frameTcp;
77 };
78
79 roboticslab::AsibotConfiguration * getJointConfiguration() const;
80
81 AsibotTcpFrame getTcpFrame() const;
82 void setTcpFrame(const AsibotTcpFrame & tcpFrameStruct);
83
84 roboticslab::AsibotConfigurationFactory * confFactory {nullptr};
85
86 AsibotTcpFrame tcpFrameStruct;
87
88 mutable std::mutex mtx;
89};
90
91#endif // __ASIBOT_SOLVER_HPP__
Contains roboticslab::ICartesianSolver.
Definition AsibotSolver_ParamsParser.h:48
The AsibotSolver implements ICartesianSolver.
Definition AsibotSolver.hpp:30
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:421
bool fwdKin(const std::vector< double > &q, std::vector< double > &x) override
Perform forward kinematics.
Definition ICartesianSolverImpl.cpp:240
bool restoreOriginalChain() override
Restore original kinematic chain.
Definition ICartesianSolverImpl.cpp:216
int getNumTcps() override
Get number of TCPs for which the solver has been configured.
Definition ICartesianSolverImpl.cpp:195
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:288
bool invDyn(const std::vector< double > &q, std::vector< double > &t) override
Perform inverse dynamics.
Definition ICartesianSolverImpl.cpp:487
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:314
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:227
int getNumJoints() override
Get number of joints for which the solver has been configured.
Definition ICartesianSolverImpl.cpp:188
bool appendLink(const std::vector< double > &x) override
Append an additional link.
Definition ICartesianSolverImpl.cpp:202
Base factory class for AsibotConfiguration.
Definition AsibotConfiguration.hpp:158
Abstract base class for a robot configuration strategy selector.
Definition AsibotConfiguration.hpp:20
Abstract base class for a cartesian solver.
Definition ICartesianSolver.h:23
reference_frame
Lists supported reference frames.
Definition ICartesianSolver.h:27
Definition AsibotSolver.hpp:74