3#ifndef __BASIC_CARTESIAN_CONTROL_HPP__
4#define __BASIC_CARTESIAN_CONTROL_HPP__
13#include <yarp/os/PeriodicThread.h>
15#include <yarp/dev/DeviceDriver.h>
16#include <yarp/dev/PolyDriver.h>
17#include <yarp/dev/ControlBoardInterfaces.h>
18#include <yarp/dev/IPreciselyTimed.h>
20#include <kdl/trajectory.hpp>
24#include "BasicCartesianControl_ParamsParser.h"
106 public yarp::os::PeriodicThread,
115 bool stat(std::vector<double> & x,
int * state =
nullptr,
double * timestamp =
nullptr)
override;
116 bool inv(
const std::vector<double> & xd, std::vector<double> & q)
override;
117 bool movj(
const std::vector<double> & xd)
override;
118 bool relj(
const std::vector<double> & xd)
override;
119 bool movl(
const std::vector<double> & xd)
override;
120 bool movv(
const std::vector<double> & xdotd)
override;
121 bool gcmp()
override;
122 bool forc(
const std::vector<double> &
fd)
override;
124 bool wait(
double timeout)
override;
125 bool tool(
const std::vector<double> & x)
override;
126 bool act(
int command)
override;
127 void pose(
const std::vector<double> & x)
override;
128 void twist(
const std::vector<double> & xdot)
override;
129 void wrench(
const std::vector<double> & w)
override;
132 bool setParameters(
const std::map<int, double> & params)
override;
139 bool open(yarp::os::Searchable & config)
override;
140 bool close()
override;
146 template <
typename Fn>
151 {
if (handler) handler(); }
153 void suppress()
const
154 { handler =
nullptr; }
157 mutable std::function<void()> handler;
160 int getCurrentState()
const;
161 void setCurrentState(
int value);
163 bool checkJointLimits(
const std::vector<double> & q);
164 bool checkJointLimits(
const std::vector<double> & q,
const std::vector<double> & qdot);
165 bool checkJointVelocities(
const std::vector<double> & qdot);
166 bool doFailFastChecks(
const std::vector<double> & initialQ);
167 bool checkControlModes(
int mode);
168 bool setControlModes(
int mode);
169 bool presetStreamingCommand(
int command);
170 bool computeIsocronousSpeeds(
const std::vector<double> & q,
const std::vector<double> & qd, std::vector<double> & qdot);
172 void handleMovj(
const std::vector<double> & q,
const StateWatcher & watcher);
173 void handleMovlVel(
const std::vector<double> & q,
const StateWatcher & watcher);
174 void handleMovlPosd(
const std::vector<double> & q,
const StateWatcher & watcher);
175 void handleMovv(
const std::vector<double> & q,
const StateWatcher & watcher);
176 void handleGcmp(
const std::vector<double> & q,
const StateWatcher & watcher);
177 void handleForc(
const std::vector<double> & q,
const std::vector<double> & qdot,
const std::vector<double> & qdotdot,
const StateWatcher & watcher);
179 yarp::dev::PolyDriver solverDevice;
182 yarp::dev::PolyDriver robotDevice;
183 yarp::dev::IControlMode * iControlMode {
nullptr};
184 yarp::dev::IEncoders * iEncoders {
nullptr};
185 yarp::dev::IPositionControl * iPositionControl {
nullptr};
186 yarp::dev::IPositionDirect * iPositionDirect {
nullptr};
187 yarp::dev::IPreciselyTimed * iPreciselyTimed {
nullptr};
188 yarp::dev::ITorqueControl * iTorqueControl {
nullptr};
189 yarp::dev::IVelocityControl * iVelocityControl {
nullptr};
197 mutable std::mutex stateMutex;
209 std::vector<double>
fd;
211 int encoderErrors {0};
212 std::atomic<bool> cmcSuccess {
true};
214 std::vector<double> qMin, qMax;
215 std::vector<double> qdotMin, qdotMax;
216 std::vector<double> qRefSpeeds;
Contains roboticslab::ICartesianControl and related vocabs.
constexpr int VOCAB_CC_NOT_SET
State: not set.
Definition ICartesianControl.h:40
constexpr int VOCAB_CC_NOT_CONTROLLING
Not controlling.
Definition ICartesianControl.h:92
Contains roboticslab::ICartesianSolver.
Definition BasicCartesianControl.hpp:144
Definition BasicCartesianControl_ParamsParser.h:52
The BasicCartesianControl class implements ICartesianControl.
Definition BasicCartesianControl.hpp:109
bool act(int command) override
Actuate tool.
Definition ICartesianControlImpl.cpp:430
bool movl(const std::vector< double > &xd) override
Linear move to target position.
Definition ICartesianControlImpl.cpp:175
void wrench(const std::vector< double > &w) override
Exert force.
Definition ICartesianControlImpl.cpp:521
bool tool(const std::vector< double > &x) override
Change tool.
Definition ICartesianControlImpl.cpp:411
bool wait(double timeout) override
Wait until completion.
Definition ICartesianControlImpl.cpp:382
std::vector< double > vmoStored
Definition BasicCartesianControl.hpp:200
bool stopControl() override
Stop control.
Definition ICartesianControlImpl.cpp:357
bool getParameters(std::map< int, double > ¶ms) override
Retrieve multiple configuration parameters.
Definition ICartesianControlImpl.cpp:732
bool getParameter(int vocab, double *value) override
Retrieve a configuration parameter.
Definition ICartesianControlImpl.cpp:674
double movementStartTime
Definition BasicCartesianControl.hpp:203
void twist(const std::vector< double > &xdot) override
Instantaneous velocity steps.
Definition ICartesianControlImpl.cpp:481
bool movj(const std::vector< double > &xd) override
Move in joint space, absolute coordinates.
Definition ICartesianControlImpl.cpp:89
void pose(const std::vector< double > &x) override
Achieve pose.
Definition ICartesianControlImpl.cpp:438
bool stat(std::vector< double > &x, int *state=nullptr, double *timestamp=nullptr) override
Current state and position.
Definition ICartesianControlImpl.cpp:37
std::vector< std::unique_ptr< KDL::Trajectory > > trajectories
Definition BasicCartesianControl.hpp:206
bool forc(const std::vector< double > &fd) override
Force control.
Definition ICartesianControlImpl.cpp:329
bool movv(const std::vector< double > &xdotd) override
Linear move with given velocity.
Definition ICartesianControlImpl.cpp:260
bool gcmp() override
Gravity compensation.
Definition ICartesianControlImpl.cpp:315
bool relj(const std::vector< double > &xd) override
Move in joint space, relative coordinates.
Definition ICartesianControlImpl.cpp:150
bool setParameters(const std::map< int, double > ¶ms) override
Set multiple configuration parameters.
Definition ICartesianControlImpl.cpp:712
bool setParameter(int vocab, double value) override
Set a configuration parameter.
Definition ICartesianControlImpl.cpp:579
std::vector< double > fd
Definition BasicCartesianControl.hpp:209
bool inv(const std::vector< double > &xd, std::vector< double > &q) override
Inverse kinematics.
Definition ICartesianControlImpl.cpp:68
Abstract base class for a cartesian controller.
Definition ICartesianControl.h:145
Abstract base class for a cartesian solver.
Definition ICartesianSolver.h:23
reference_frame
Lists supported reference frames.
Definition ICartesianSolver.h:27