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#include <vector>
8
9#include <yarp/os/Searchable.h>
10#include <yarp/dev/DeviceDriver.h>
11#include <yarp/sig/Matrix.h>
12
13#include "AsibotConfiguration.hpp"
14#include "ICartesianSolver.h"
15
16namespace roboticslab
17{
18
30class AsibotSolver : public yarp::dev::DeviceDriver,
31 public ICartesianSolver
32{
33public:
34 // -------- ICartesianSolver declarations. Implementation in ICartesianSolverImpl.cpp --------
35
36 // Get number of joints for which the solver has been configured.
37 int getNumJoints() override;
38
39 // Get number of TCPs for which the solver has been configured.
40 int getNumTcps() override;
41
42 // Append an additional link.
43 bool appendLink(const std::vector<double> &x) override;
44
45 // Restore original kinematic chain.
46 bool restoreOriginalChain() override;
47
48 // Change reference frame.
49 bool changeOrigin(const std::vector<double> &x_old_obj,
50 const std::vector<double> &x_new_old,
51 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,
61 reference_frame frame) override;
62
63 // Perform differential inverse kinematics.
64 bool diffInvKin(const std::vector<double> &q, const std::vector<double> &xdot, std::vector<double> &qdot,
65 reference_frame frame) override;
66
67 // Perform inverse dynamics.
68 bool invDyn(const std::vector<double> &q, std::vector<double> &t) override;
69
70 // Perform inverse dynamics.
71 bool invDyn(const std::vector<double> &q, const std::vector<double> &qdot, const std::vector<double> &qdotdot,
72 const std::vector<double> &ftip, std::vector<double> &t, reference_frame frame) override;
73
74 // -------- DeviceDriver declarations. Implementation in DeviceDriverImpl.cpp --------
75 bool open(yarp::os::Searchable& config) override;
76 bool close() override;
77
78private:
80 {
81 bool hasFrame;
82 yarp::sig::Matrix frameTcp;
83 };
84
85 AsibotConfiguration * getConfiguration() const;
86
87 AsibotTcpFrame getTcpFrame() const;
88 void setTcpFrame(const AsibotTcpFrame & tcpFrameStruct);
89
90 double A0, A1, A2, A3; // link lengths
91
92 std::vector<double> qMin, qMax;
93
94 AsibotConfigurationFactory * confFactory {nullptr};
95
96 AsibotTcpFrame tcpFrameStruct;
97
98 mutable std::mutex mtx;
99};
100
101} // namespace roboticslab
102
103#endif // __ASIBOT_SOLVER_HPP__
Contains roboticslab::ICartesianSolver.
Base factory class for AsibotConfiguration.
Definition AsibotConfiguration.hpp:158
Abstract base class for a robot configuration strategy selector.
Definition AsibotConfiguration.hpp:20
The AsibotSolver implements ICartesianSolver.
Definition AsibotSolver.hpp:32
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
Abstract base class for a cartesian solver.
Definition ICartesianSolver.h:23
reference_frame
Lists supported reference frames.
Definition ICartesianSolver.h:27
The main, catch-all namespace for Robotics Lab UC3M.
Definition groups.dox:6
Definition AsibotSolver.hpp:80