kinematics-dynamics
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 //-----------------------------------------------------------------------------------------------------------------------------------
23 // USING `int` INSTEAD OF `yarp::conf::vocab32_t` BECAUSE OF SWIG: https://github.com/roboticslab-uc3m/kinematics-dynamics/issues/180
24 //-----------------------------------------------------------------------------------------------------------------------------------
25 
34 // General-purpose vocabs
35 constexpr int VOCAB_CC_OK = yarp::os::createVocab32('o','k');
36 constexpr int VOCAB_CC_FAILED = yarp::os::createVocab32('f','a','i','l');
37 constexpr int VOCAB_CC_SET = yarp::os::createVocab32('s','e','t');
38 constexpr int VOCAB_CC_GET = yarp::os::createVocab32('g','e','t');
39 constexpr int VOCAB_CC_NOT_SET = yarp::os::createVocab32('n','s','e','t');
40 
51 // RPC commands
52 constexpr int VOCAB_CC_STAT = yarp::os::createVocab32('s','t','a','t');
53 constexpr int VOCAB_CC_INV = yarp::os::createVocab32('i','n','v');
54 constexpr int VOCAB_CC_MOVJ = yarp::os::createVocab32('m','o','v','j');
55 constexpr int VOCAB_CC_RELJ = yarp::os::createVocab32('r','e','l','j');
56 constexpr int VOCAB_CC_MOVL = yarp::os::createVocab32('m','o','v','l');
57 constexpr int VOCAB_CC_MOVV = yarp::os::createVocab32('m','o','v','v');
58 constexpr int VOCAB_CC_GCMP = yarp::os::createVocab32('g','c','m','p');
59 constexpr int VOCAB_CC_FORC = yarp::os::createVocab32('f','o','r','c');
60 constexpr int VOCAB_CC_STOP = yarp::os::createVocab32('s','t','o','p');
61 constexpr int VOCAB_CC_WAIT = yarp::os::createVocab32('w','a','i','t');
62 constexpr int VOCAB_CC_TOOL = yarp::os::createVocab32('t','o','o','l');
63 constexpr int VOCAB_CC_ACT = yarp::os::createVocab32('a','c','t');
64 
75 // Streaming commands
76 constexpr int VOCAB_CC_POSE = yarp::os::createVocab32('p','o','s','e');
77 #ifndef SWIG_PREPROCESSOR_SHOULD_SKIP_THIS
78 [[deprecated("use `VOCAB_CC_POSE` instead")]]
79 constexpr int VOCAB_CC_MOVI = yarp::os::createVocab32('m','o','v','i');
80 #endif
81 constexpr int VOCAB_CC_TWIST = yarp::os::createVocab32('t','w','s','t');
82 constexpr int VOCAB_CC_WRENCH = yarp::os::createVocab32('w','r','n','c');
83 
94 // Control state
95 constexpr int VOCAB_CC_NOT_CONTROLLING = yarp::os::createVocab32('c','c','n','c');
96 constexpr int VOCAB_CC_MOVJ_CONTROLLING = yarp::os::createVocab32('c','c','j','c');
97 constexpr int VOCAB_CC_MOVL_CONTROLLING = yarp::os::createVocab32('c','c','l','c');
98 constexpr int VOCAB_CC_MOVV_CONTROLLING = yarp::os::createVocab32('c','c','v','c');
99 constexpr int VOCAB_CC_GCMP_CONTROLLING = yarp::os::createVocab32('c','c','g','c');
100 constexpr int VOCAB_CC_FORC_CONTROLLING = yarp::os::createVocab32('c','c','f','c');
101 
113 // Actuator control
114 constexpr int VOCAB_CC_ACTUATOR_NONE = yarp::os::createVocab32('a','c','n');
115 constexpr int VOCAB_CC_ACTUATOR_CLOSE_GRIPPER = yarp::os::createVocab32('a','c','c','g');
116 constexpr int VOCAB_CC_ACTUATOR_OPEN_GRIPPER = yarp::os::createVocab32('a','c','o','g');
117 constexpr int VOCAB_CC_ACTUATOR_STOP_GRIPPER = yarp::os::createVocab32('a','c','s','g');
118 constexpr int VOCAB_CC_ACTUATOR_GENERIC = yarp::os::createVocab32('a','c','g');
119 
128 // Controller configuration (parameter keys)
129 constexpr int VOCAB_CC_CONFIG_PARAMS = yarp::os::createVocab32('p','r','m','s');
130 constexpr int VOCAB_CC_CONFIG_GAIN = yarp::os::createVocab32('c','p','c','g');
131 constexpr int VOCAB_CC_CONFIG_TRAJ_DURATION = yarp::os::createVocab32('c','p','t','d');
132 constexpr int VOCAB_CC_CONFIG_CMC_PERIOD = yarp::os::createVocab32('c','p','c','p');
133 constexpr int VOCAB_CC_CONFIG_WAIT_PERIOD = yarp::os::createVocab32('c','p','w','p');
134 constexpr int VOCAB_CC_CONFIG_FRAME = yarp::os::createVocab32('c','p','f');
135 constexpr int VOCAB_CC_CONFIG_STREAMING_CMD = yarp::os::createVocab32('c','p','s','c');
136 
139 namespace roboticslab
140 {
141 
146 {
147 public:
149  virtual ~ICartesianControl() = default;
150 
151  //--------------------- RPC commands ---------------------
152 
175  virtual bool stat(std::vector<double> &x, int * state = nullptr, double * timestamp = nullptr) = 0;
176 
189  virtual bool inv(const std::vector<double> &xd, std::vector<double> &q) = 0;
190 
205  virtual bool movj(const std::vector<double> &xd) = 0;
206 
221  virtual bool relj(const std::vector<double> &xd) = 0;
222 
234  virtual bool movl(const std::vector<double> &xd) = 0;
235 
247  virtual bool movv(const std::vector<double> &xdotd) = 0;
248 
256  virtual bool gcmp() = 0;
257 
269  virtual bool forc(const std::vector<double> &fd) = 0;
270 
278  virtual bool stopControl() = 0;
279 
291  virtual bool wait(double timeout = 0.0) = 0;
292 
304  virtual bool tool(const std::vector<double> &x) = 0;
305 
315  virtual bool act(int command) = 0;
316 
319  //--------------------- Streaming commands ---------------------
320 
340  virtual void pose(const std::vector<double> &x) = 0;
341 
342 #ifndef SWIG_PREPROCESSOR_SHOULD_SKIP_THIS
343  [[deprecated("use `pose` instead")]]
344  virtual void movi(const std::vector<double> &x)
345  {
346  pose(x);
347  }
348 #endif
349 
359  virtual void twist(const std::vector<double> &xdot) = 0;
360 
369  virtual void wrench(const std::vector<double> &w) = 0;
370 
373  //--------------------- Configuration accessors ---------------------
374 
394  virtual bool setParameter(int vocab, double value) = 0;
395 
406  virtual bool getParameter(int vocab, double * value) = 0;
407 
417  virtual bool setParameters(const std::map<int, double> & params) = 0;
418 
428  virtual bool getParameters(std::map<int, double> & params) = 0;
429 
431 };
432 
433 } // namespace roboticslab
434 
437 #endif // __I_CARTESIAN_CONTROL__
constexpr int VOCAB_CC_STAT
Current state and position.
Definition: ICartesianControl.h:52
constexpr int VOCAB_CC_RELJ
Move in joint space, relative coordinates.
Definition: ICartesianControl.h:55
constexpr int VOCAB_CC_ACTUATOR_CLOSE_GRIPPER
Close gripper.
Definition: ICartesianControl.h:115
constexpr int VOCAB_CC_MOVJ
Move in joint space, absolute coordinates.
Definition: ICartesianControl.h:54
constexpr int VOCAB_CC_ACTUATOR_NONE
No actuator or no action.
Definition: ICartesianControl.h:114
constexpr int VOCAB_CC_TOOL
Change tool.
Definition: ICartesianControl.h:62
constexpr int VOCAB_CC_FORC
Force control.
Definition: ICartesianControl.h:59
constexpr int VOCAB_CC_FORC_CONTROLLING
Controlling FORC commands.
Definition: ICartesianControl.h:100
constexpr int VOCAB_CC_GCMP_CONTROLLING
Controlling GCMP commands.
Definition: ICartesianControl.h:99
constexpr int VOCAB_CC_CONFIG_TRAJ_DURATION
Trajectory duration.
Definition: ICartesianControl.h:131
constexpr int VOCAB_CC_GCMP
Gravity compensation.
Definition: ICartesianControl.h:58
constexpr int VOCAB_CC_SET
Setter.
Definition: ICartesianControl.h:37
constexpr int VOCAB_CC_CONFIG_PARAMS
Parameter group.
Definition: ICartesianControl.h:129
constexpr int VOCAB_CC_INV
Inverse kinematics.
Definition: ICartesianControl.h:53
constexpr int VOCAB_CC_CONFIG_FRAME
Reference frame.
Definition: ICartesianControl.h:134
constexpr int VOCAB_CC_ACTUATOR_STOP_GRIPPER
Stop gripper.
Definition: ICartesianControl.h:117
constexpr int VOCAB_CC_OK
Success.
Definition: ICartesianControl.h:35
constexpr int VOCAB_CC_GET
Getter.
Definition: ICartesianControl.h:38
constexpr int VOCAB_CC_WRENCH
Exert force.
Definition: ICartesianControl.h:82
constexpr int VOCAB_CC_NOT_SET
State: not set.
Definition: ICartesianControl.h:39
constexpr int VOCAB_CC_ACTUATOR_GENERIC
Generic actuator.
Definition: ICartesianControl.h:118
constexpr int VOCAB_CC_ACT
Actuate tool.
Definition: ICartesianControl.h:63
constexpr int VOCAB_CC_TWIST
Instantaneous velocity steps.
Definition: ICartesianControl.h:81
constexpr int VOCAB_CC_CONFIG_WAIT_PERIOD
Check period of 'wait' command [ms].
Definition: ICartesianControl.h:133
constexpr int VOCAB_CC_WAIT
Wait motion done.
Definition: ICartesianControl.h:61
constexpr int VOCAB_CC_FAILED
Failure.
Definition: ICartesianControl.h:36
constexpr int VOCAB_CC_NOT_CONTROLLING
Not controlling.
Definition: ICartesianControl.h:95
constexpr int VOCAB_CC_CONFIG_CMC_PERIOD
CMC period [ms].
Definition: ICartesianControl.h:132
constexpr int VOCAB_CC_MOVV_CONTROLLING
Controlling MOVV commands.
Definition: ICartesianControl.h:98
constexpr int VOCAB_CC_CONFIG_GAIN
Controller gain.
Definition: ICartesianControl.h:130
constexpr int VOCAB_CC_CONFIG_STREAMING_CMD
Preset streaming command.
Definition: ICartesianControl.h:135
constexpr int VOCAB_CC_MOVL_CONTROLLING
Controlling MOVL commands.
Definition: ICartesianControl.h:97
constexpr int VOCAB_CC_STOP
Stop control.
Definition: ICartesianControl.h:60
constexpr int VOCAB_CC_ACTUATOR_OPEN_GRIPPER
Open gripper.
Definition: ICartesianControl.h:116
constexpr int VOCAB_CC_POSE
Achieve pose.
Definition: ICartesianControl.h:76
constexpr int VOCAB_CC_MOVL
Linear move to target position.
Definition: ICartesianControl.h:56
constexpr int VOCAB_CC_MOVV
Linear move with given velocity.
Definition: ICartesianControl.h:57
constexpr int VOCAB_CC_MOVJ_CONTROLLING
Controlling MOVJ commands.
Definition: ICartesianControl.h:96
Contains roboticslab::ICartesianSolver.
Abstract base class for a cartesian controller.
Definition: ICartesianControl.h:146
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