3#ifndef __ASIBOT_SOLVER_HPP__
4#define __ASIBOT_SOLVER_HPP__
8#include <yarp/os/Searchable.h>
9#include <yarp/dev/DeviceDriver.h>
10#include <yarp/sig/Matrix.h>
12#include "AsibotConfiguration.hpp"
14#include "AsibotSolver_ParamsParser.h"
41 bool appendLink(
const std::vector<double> &x)
override;
47 bool changeOrigin(
const std::vector<double> &x_old_obj,
const std::vector<double> &x_new_old, std::vector<double> &x_new_obj)
override;
50 bool fwdKin(
const std::vector<double> &q, std::vector<double> &x)
override;
53 bool poseDiff(
const std::vector<double> &xLhs,
const std::vector<double> &xRhs, std::vector<double> &xOut)
override;
56 bool invKin(
const std::vector<double> &xd,
const std::vector<double> &qGuess, std::vector<double> &q,
reference_frame frame)
override;
59 bool diffInvKin(
const std::vector<double> &q,
const std::vector<double> &xdot, std::vector<double> &qdot,
reference_frame frame)
override;
62 bool invDyn(
const std::vector<double> &q, std::vector<double> &t)
override;
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;
69 bool open(yarp::os::Searchable& config)
override;
70 bool close()
override;
76 yarp::sig::Matrix frameTcp;
86 AsibotTcpFrame tcpFrameStruct;
88 mutable std::mutex mtx;
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