kinematics-dynamics
Loading...
Searching...
No Matches
ICartesianControl.h
Go to the documentation of this file.
1// -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2
3#ifndef __I_CARTESIAN_CONTROL__
4#define __I_CARTESIAN_CONTROL__
5
6#include <map>
7#include <vector>
8
9#include <yarp/os/Vocab.h>
10
11#include <ICartesianSolver.h>
12
20//---------------------------------------------------------------------------------------------------------------
21// KEEP VOCAB LIST AND DOCUMENTATION IN SYNC WITH roboticslab::RpcResponder::makeUsage AT CartesianControlServer/
22// and roboticslab::CartesianControlServerROS2::configureRosParameters AT CartesianControlServerROS2/
23//-----------------------------------------------------------------------------------------------------------------------------------
24// USING `int` INSTEAD OF `yarp::conf::vocab32_t` BECAUSE OF SWIG: https://github.com/roboticslab-uc3m/kinematics-dynamics/issues/180
25//-----------------------------------------------------------------------------------------------------------------------------------
26
35// General-purpose vocabs
36constexpr int VOCAB_CC_OK = yarp::os::createVocab32('o','k');
37constexpr int VOCAB_CC_FAILED = yarp::os::createVocab32('f','a','i','l');
38constexpr int VOCAB_CC_SET = yarp::os::createVocab32('s','e','t');
39constexpr int VOCAB_CC_GET = yarp::os::createVocab32('g','e','t');
40constexpr int VOCAB_CC_NOT_SET = yarp::os::createVocab32('n','s','e','t');
41
52// RPC commands
53constexpr int VOCAB_CC_STAT = yarp::os::createVocab32('s','t','a','t');
54constexpr int VOCAB_CC_INV = yarp::os::createVocab32('i','n','v');
55constexpr int VOCAB_CC_MOVJ = yarp::os::createVocab32('m','o','v','j');
56constexpr int VOCAB_CC_RELJ = yarp::os::createVocab32('r','e','l','j');
57constexpr int VOCAB_CC_MOVL = yarp::os::createVocab32('m','o','v','l');
58constexpr int VOCAB_CC_MOVV = yarp::os::createVocab32('m','o','v','v');
59constexpr int VOCAB_CC_GCMP = yarp::os::createVocab32('g','c','m','p');
60constexpr int VOCAB_CC_FORC = yarp::os::createVocab32('f','o','r','c');
61constexpr int VOCAB_CC_STOP = yarp::os::createVocab32('s','t','o','p');
62constexpr int VOCAB_CC_WAIT = yarp::os::createVocab32('w','a','i','t');
63constexpr int VOCAB_CC_TOOL = yarp::os::createVocab32('t','o','o','l');
64constexpr int VOCAB_CC_ACT = yarp::os::createVocab32('a','c','t');
65
76// Streaming commands
77constexpr int VOCAB_CC_POSE = yarp::os::createVocab32('p','o','s','e');
78constexpr int VOCAB_CC_TWIST = yarp::os::createVocab32('t','w','s','t');
79constexpr int VOCAB_CC_WRENCH = yarp::os::createVocab32('w','r','n','c');
80
91// Control state
92constexpr int VOCAB_CC_NOT_CONTROLLING = yarp::os::createVocab32('c','c','n','c');
93constexpr int VOCAB_CC_MOVJ_CONTROLLING = yarp::os::createVocab32('c','c','j','c');
94constexpr int VOCAB_CC_MOVL_CONTROLLING = yarp::os::createVocab32('c','c','l','c');
95constexpr int VOCAB_CC_MOVV_CONTROLLING = yarp::os::createVocab32('c','c','v','c');
96constexpr int VOCAB_CC_GCMP_CONTROLLING = yarp::os::createVocab32('c','c','g','c');
97constexpr int VOCAB_CC_FORC_CONTROLLING = yarp::os::createVocab32('c','c','f','c');
98
110// Actuator control
111constexpr int VOCAB_CC_ACTUATOR_NONE = yarp::os::createVocab32('a','c','n');
112constexpr int VOCAB_CC_ACTUATOR_CLOSE_GRIPPER = yarp::os::createVocab32('a','c','c','g');
113constexpr int VOCAB_CC_ACTUATOR_OPEN_GRIPPER = yarp::os::createVocab32('a','c','o','g');
114constexpr int VOCAB_CC_ACTUATOR_STOP_GRIPPER = yarp::os::createVocab32('a','c','s','g');
115constexpr int VOCAB_CC_ACTUATOR_GENERIC = yarp::os::createVocab32('a','c','g');
116
125// Controller configuration (parameter keys)
126constexpr int VOCAB_CC_CONFIG_PARAMS = yarp::os::createVocab32('p','r','m','s');
127constexpr int VOCAB_CC_CONFIG_GAIN = yarp::os::createVocab32('c','p','c','g');
128constexpr int VOCAB_CC_CONFIG_TRAJ_DURATION = yarp::os::createVocab32('c','p','t','d');
129constexpr int VOCAB_CC_CONFIG_TRAJ_REF_SPD = yarp::os::createVocab32('c','p','t','s');
130constexpr int VOCAB_CC_CONFIG_TRAJ_REF_ACC = yarp::os::createVocab32('c','p','t','a');
131constexpr int VOCAB_CC_CONFIG_CMC_PERIOD = yarp::os::createVocab32('c','p','c','p');
132constexpr int VOCAB_CC_CONFIG_WAIT_PERIOD = yarp::os::createVocab32('c','p','w','p');
133constexpr int VOCAB_CC_CONFIG_FRAME = yarp::os::createVocab32('c','p','f');
134constexpr int VOCAB_CC_CONFIG_STREAMING_CMD = yarp::os::createVocab32('c','p','s','c');
135
138namespace roboticslab
139{
140
145{
146public:
148 virtual ~ICartesianControl() = default;
149
150 //--------------------- RPC commands ---------------------
151
174 virtual bool stat(std::vector<double> &x, int * state = nullptr, double * timestamp = nullptr) = 0;
175
188 virtual bool inv(const std::vector<double> &xd, std::vector<double> &q) = 0;
189
204 virtual bool movj(const std::vector<double> &xd) = 0;
205
220 virtual bool relj(const std::vector<double> &xd) = 0;
221
233 virtual bool movl(const std::vector<double> &xd) = 0;
234
246 virtual bool movv(const std::vector<double> &xdotd) = 0;
247
255 virtual bool gcmp() = 0;
256
268 virtual bool forc(const std::vector<double> &fd) = 0;
269
277 virtual bool stopControl() = 0;
278
290 virtual bool wait(double timeout = 0.0) = 0;
291
303 virtual bool tool(const std::vector<double> &x) = 0;
304
314 virtual bool act(int command) = 0;
315
318 //--------------------- Streaming commands ---------------------
319
339 virtual void pose(const std::vector<double> &x) = 0;
340
350 virtual void twist(const std::vector<double> &xdot) = 0;
351
360 virtual void wrench(const std::vector<double> &w) = 0;
361
364 //--------------------- Configuration accessors ---------------------
365
385 virtual bool setParameter(int vocab, double value) = 0;
386
397 virtual bool getParameter(int vocab, double * value) = 0;
398
408 virtual bool setParameters(const std::map<int, double> & params) = 0;
409
419 virtual bool getParameters(std::map<int, double> & params) = 0;
420
422};
423
424} // namespace roboticslab
425
428#endif // __I_CARTESIAN_CONTROL__
constexpr int VOCAB_CC_STAT
Current state and position.
Definition ICartesianControl.h:53
constexpr int VOCAB_CC_RELJ
Move in joint space, relative coordinates.
Definition ICartesianControl.h:56
constexpr int VOCAB_CC_ACTUATOR_CLOSE_GRIPPER
Close gripper.
Definition ICartesianControl.h:112
constexpr int VOCAB_CC_MOVJ
Move in joint space, absolute coordinates.
Definition ICartesianControl.h:55
constexpr int VOCAB_CC_ACTUATOR_NONE
No actuator or no action.
Definition ICartesianControl.h:111
constexpr int VOCAB_CC_TOOL
Change tool.
Definition ICartesianControl.h:63
constexpr int VOCAB_CC_FORC
Force control.
Definition ICartesianControl.h:60
constexpr int VOCAB_CC_FORC_CONTROLLING
Controlling FORC commands.
Definition ICartesianControl.h:97
constexpr int VOCAB_CC_GCMP_CONTROLLING
Controlling GCMP commands.
Definition ICartesianControl.h:96
constexpr int VOCAB_CC_CONFIG_TRAJ_DURATION
Trajectory duration [s].
Definition ICartesianControl.h:128
constexpr int VOCAB_CC_CONFIG_TRAJ_REF_SPD
Trajectory reference speed [m/s].
Definition ICartesianControl.h:129
constexpr int VOCAB_CC_GCMP
Gravity compensation.
Definition ICartesianControl.h:59
constexpr int VOCAB_CC_SET
Setter.
Definition ICartesianControl.h:38
constexpr int VOCAB_CC_CONFIG_PARAMS
Parameter group.
Definition ICartesianControl.h:126
constexpr int VOCAB_CC_INV
Inverse kinematics.
Definition ICartesianControl.h:54
constexpr int VOCAB_CC_CONFIG_TRAJ_REF_ACC
Trajectory reference acceleration [m/s^2].
Definition ICartesianControl.h:130
constexpr int VOCAB_CC_CONFIG_FRAME
Reference frame.
Definition ICartesianControl.h:133
constexpr int VOCAB_CC_ACTUATOR_STOP_GRIPPER
Stop gripper.
Definition ICartesianControl.h:114
constexpr int VOCAB_CC_OK
Success.
Definition ICartesianControl.h:36
constexpr int VOCAB_CC_GET
Getter.
Definition ICartesianControl.h:39
constexpr int VOCAB_CC_WRENCH
Exert force.
Definition ICartesianControl.h:79
constexpr int VOCAB_CC_NOT_SET
State: not set.
Definition ICartesianControl.h:40
constexpr int VOCAB_CC_ACTUATOR_GENERIC
Generic actuator.
Definition ICartesianControl.h:115
constexpr int VOCAB_CC_ACT
Actuate tool.
Definition ICartesianControl.h:64
constexpr int VOCAB_CC_TWIST
Instantaneous velocity steps.
Definition ICartesianControl.h:78
constexpr int VOCAB_CC_CONFIG_WAIT_PERIOD
Check period of 'wait' command [ms].
Definition ICartesianControl.h:132
constexpr int VOCAB_CC_WAIT
Wait motion done.
Definition ICartesianControl.h:62
constexpr int VOCAB_CC_FAILED
Failure.
Definition ICartesianControl.h:37
constexpr int VOCAB_CC_NOT_CONTROLLING
Not controlling.
Definition ICartesianControl.h:92
constexpr int VOCAB_CC_CONFIG_CMC_PERIOD
CMC period [ms].
Definition ICartesianControl.h:131
constexpr int VOCAB_CC_MOVV_CONTROLLING
Controlling MOVV commands.
Definition ICartesianControl.h:95
constexpr int VOCAB_CC_CONFIG_GAIN
Controller gain.
Definition ICartesianControl.h:127
constexpr int VOCAB_CC_CONFIG_STREAMING_CMD
Preset streaming command.
Definition ICartesianControl.h:134
constexpr int VOCAB_CC_MOVL_CONTROLLING
Controlling MOVL commands.
Definition ICartesianControl.h:94
constexpr int VOCAB_CC_STOP
Stop control.
Definition ICartesianControl.h:61
constexpr int VOCAB_CC_ACTUATOR_OPEN_GRIPPER
Open gripper.
Definition ICartesianControl.h:113
constexpr int VOCAB_CC_POSE
Achieve pose.
Definition ICartesianControl.h:77
constexpr int VOCAB_CC_MOVL
Linear move to target position.
Definition ICartesianControl.h:57
constexpr int VOCAB_CC_MOVV
Linear move with given velocity.
Definition ICartesianControl.h:58
constexpr int VOCAB_CC_MOVJ_CONTROLLING
Controlling MOVJ commands.
Definition ICartesianControl.h:93
Contains roboticslab::ICartesianSolver.
Abstract base class for a cartesian controller.
Definition ICartesianControl.h:145
virtual ~ICartesianControl()=default
Destructor.
virtual bool stat(std::vector< double > &x, int *state=nullptr, double *timestamp=nullptr)=0
Current state and position.
virtual bool act(int command)=0
Actuate tool.
virtual bool tool(const std::vector< double > &x)=0
Change tool.
virtual bool relj(const std::vector< double > &xd)=0
Move in joint space, relative coordinates.
virtual bool setParameter(int vocab, double value)=0
Set a configuration parameter.
virtual bool setParameters(const std::map< int, double > &params)=0
Set multiple configuration parameters.
virtual bool getParameter(int vocab, double *value)=0
Retrieve a configuration parameter.
virtual bool movl(const std::vector< double > &xd)=0
Linear move to target position.
virtual bool wait(double timeout=0.0)=0
Wait until completion.
virtual void twist(const std::vector< double > &xdot)=0
Instantaneous velocity steps.
virtual bool gcmp()=0
Gravity compensation.
virtual bool movv(const std::vector< double > &xdotd)=0
Linear move with given velocity.
virtual bool inv(const std::vector< double > &xd, std::vector< double > &q)=0
Inverse kinematics.
virtual bool getParameters(std::map< int, double > &params)=0
Retrieve multiple configuration parameters.
virtual void pose(const std::vector< double > &x)=0
Achieve pose.
virtual bool forc(const std::vector< double > &fd)=0
Force control.
virtual bool movj(const std::vector< double > &xd)=0
Move in joint space, absolute coordinates.
virtual bool stopControl()=0
Stop control.
virtual void wrench(const std::vector< double > &w)=0
Exert force.
The main, catch-all namespace for Robotics Lab UC3M.
Definition groups.dox:6