3 #ifndef __I_CARTESIAN_CONTROL__
4 #define __I_CARTESIAN_CONTROL__
9 #include <yarp/os/Vocab.h>
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');
175 virtual bool stat(std::vector<double> &x,
int * state =
nullptr,
double * timestamp =
nullptr) = 0;
189 virtual bool inv(
const std::vector<double> &xd, std::vector<double> &q) = 0;
205 virtual bool movj(
const std::vector<double> &xd) = 0;
221 virtual bool relj(
const std::vector<double> &xd) = 0;
234 virtual bool movl(
const std::vector<double> &xd) = 0;
247 virtual bool movv(
const std::vector<double> &xdotd) = 0;
269 virtual bool forc(
const std::vector<double> &fd) = 0;
291 virtual bool wait(
double timeout = 0.0) = 0;
304 virtual bool tool(
const std::vector<double> &x) = 0;
315 virtual bool act(
int command) = 0;
340 virtual void pose(
const std::vector<double> &x) = 0;
342 #ifndef SWIG_PREPROCESSOR_SHOULD_SKIP_THIS
343 [[deprecated(
"use `pose` instead")]]
344 virtual void movi(
const std::vector<double> &x)
359 virtual void twist(
const std::vector<double> &xdot) = 0;
369 virtual void wrench(
const std::vector<double> &w) = 0;
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 > ¶ms)=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 > ¶ms)=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