kinematics-dynamics
Public Member Functions | List of all members
roboticslab::ICartesianControl Class Referenceabstract

Abstract base class for a cartesian controller.

#include <ICartesianControl.h>

Inheritance diagram for roboticslab::ICartesianControl:
roboticslab::BasicCartesianControl roboticslab::CartesianControlClient

Public Member Functions

virtual ~ICartesianControl ()=default
 Destructor.
 
RPC commands

RPC commands with success/failure response.

virtual bool stat (std::vector< double > &x, int *state=nullptr, double *timestamp=nullptr)=0
 Current state and position. More...
 
virtual bool inv (const std::vector< double > &xd, std::vector< double > &q)=0
 Inverse kinematics. More...
 
virtual bool movj (const std::vector< double > &xd)=0
 Move in joint space, absolute coordinates. More...
 
virtual bool relj (const std::vector< double > &xd)=0
 Move in joint space, relative coordinates. More...
 
virtual bool movl (const std::vector< double > &xd)=0
 Linear move to target position. More...
 
virtual bool movv (const std::vector< double > &xdotd)=0
 Linear move with given velocity. More...
 
virtual bool gcmp ()=0
 Gravity compensation. More...
 
virtual bool forc (const std::vector< double > &fd)=0
 Force control. More...
 
virtual bool stopControl ()=0
 Stop control. More...
 
virtual bool wait (double timeout=0.0)=0
 Wait until completion. More...
 
virtual bool tool (const std::vector< double > &x)=0
 Change tool. More...
 
virtual bool act (int command)=0
 Actuate tool. More...
 
Streaming commands

High-frequency streaming commands, no acknowledge.

virtual void pose (const std::vector< double > &x)=0
 Achieve pose. More...
 
virtual void movi (const std::vector< double > &x)
 
virtual void twist (const std::vector< double > &xdot)=0
 Instantaneous velocity steps. More...
 
virtual void wrench (const std::vector< double > &w)=0
 Exert force. More...
 
Configuration accessors

Configuration setters and getters with success/failure response.

virtual bool setParameter (int vocab, double value)=0
 Set a configuration parameter. More...
 
virtual bool getParameter (int vocab, double *value)=0
 Retrieve a configuration parameter. More...
 
virtual bool setParameters (const std::map< int, double > &params)=0
 Set multiple configuration parameters. More...
 
virtual bool getParameters (std::map< int, double > &params)=0
 Retrieve multiple configuration parameters. More...
 

Member Function Documentation

◆ act()

virtual bool roboticslab::ICartesianControl::act ( int  command)
pure virtual

Send control command to actuate the robot's tool, if available.

Parameters
commandOne of available actuator vocabs.
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ forc()

virtual bool roboticslab::ICartesianControl::forc ( const std::vector< double > &  fd)
pure virtual

Apply desired forces in task space.

Parameters
fd6-element vector describing desired force exerted by the TCP in cartesian space; first three elements denote linear force (Newton), last three denote torque (Newton*meters).
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ gcmp()

virtual bool roboticslab::ICartesianControl::gcmp ( )
pure virtual

Enable gravity compensation.

Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ getParameter()

virtual bool roboticslab::ICartesianControl::getParameter ( int  vocab,
double *  value 
)
pure virtual

Ask the controller to retrieve a parameter of 'double' type.

Parameters
vocabYARP-encoded vocab (parameter key).
valueParameter value encoded as a double.
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ getParameters()

virtual bool roboticslab::ICartesianControl::getParameters ( std::map< int, double > &  params)
pure virtual

Ask the controller to retrieve all available parameters at once.

Parameters
paramsDictionary of YARP-encoded vocabs as keys and their values.
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ inv()

virtual bool roboticslab::ICartesianControl::inv ( const std::vector< double > &  xd,
std::vector< double > &  q 
)
pure virtual

Perform inverse kinematics (using robot position as initial guess), but do not move.

Parameters
xd6-element vector describing desired position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
qVector describing current position in joint space (meters or degrees).
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ movj()

virtual bool roboticslab::ICartesianControl::movj ( const std::vector< double > &  xd)
pure virtual

Perform inverse kinematics and move to desired position in joint space using absolute coordinates.

Parameters
xd6-element vector describing desired position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
See also
relj (relative coordinates)
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ movl()

virtual bool roboticslab::ICartesianControl::movl ( const std::vector< double > &  xd)
pure virtual

Move to end position along a line trajectory.

Parameters
xd6-element vector describing desired position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ movv()

virtual bool roboticslab::ICartesianControl::movv ( const std::vector< double > &  xdotd)
pure virtual

Move along a line with constant velocity.

Parameters
xdotd6-element vector describing desired velocity in cartesian space; first three elements denote translational velocity (meters/second), last three denote angular velocity (radians/second).
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ pose()

virtual void roboticslab::ICartesianControl::pose ( const std::vector< double > &  x)
pure virtual

Move to desired position instantaneously, no further intermediate calculations are expected other than computing the inverse kinematics.

Parameters
x6-element vector describing desired instantaneous pose in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ relj()

virtual bool roboticslab::ICartesianControl::relj ( const std::vector< double > &  xd)
pure virtual

Perform inverse kinematics and move to desired position in joint space using relative coordinates.

Parameters
xd6-element vector describing desired offset in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
See also
movj (absolute coordinates)
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ setParameter()

virtual bool roboticslab::ICartesianControl::setParameter ( int  vocab,
double  value 
)
pure virtual

Ask the controller to store or update a parameter of 'double' type.

Parameters
vocabYARP-encoded vocab (parameter key).
valueParameter value encoded as a double.
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ setParameters()

virtual bool roboticslab::ICartesianControl::setParameters ( const std::map< int, double > &  params)
pure virtual

Ask the controller to store or update multiple parameters at once.

Parameters
paramsDictionary of YARP-encoded vocabs as keys and their values.
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ stat()

virtual bool roboticslab::ICartesianControl::stat ( std::vector< double > &  x,
int *  state = nullptr,
double *  timestamp = nullptr 
)
pure virtual

Inform on control state, get robot position and perform forward kinematics.

Parameters
x6-element vector describing current position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
stateIdentifier for a cartesian control vocab.
timestampRemote encoder acquisition time.
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ stopControl()

virtual bool roboticslab::ICartesianControl::stopControl ( )
pure virtual

Halt current control loop if any and cease movement.

Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ tool()

virtual bool roboticslab::ICartesianControl::tool ( const std::vector< double > &  x)
pure virtual

Unload current tool if any and append new tool frame to the kinematic chain.

Parameters
x6-element vector describing new tool tip with regard to current end-effector frame in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
Returns
true on success, false otherwise

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ twist()

virtual void roboticslab::ICartesianControl::twist ( const std::vector< double > &  xdot)
pure virtual

Move in instantaneous velocity increments.

Parameters
xdot6-element vector describing velocity increments in cartesian space; first three elements denote translational velocity (meters/second), last three denote angular velocity (radians/second).

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ wait()

virtual bool roboticslab::ICartesianControl::wait ( double  timeout = 0.0)
pure virtual

Block execution until the movement is completed, errors occur or timeout is reached.

Parameters
timeoutTimeout in seconds, '0.0' means no timeout.
Returns
true on success, false if errors occurred during the execution of the trajectory

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.

◆ wrench()

virtual void roboticslab::ICartesianControl::wrench ( const std::vector< double > &  w)
pure virtual

Make the TCP exert the desired force instantaneously.

Parameters
w6-element vector describing desired force exerted by the TCP in cartesian space; first three elements denote linear force (Newton), last three denote torque (Newton*meters).

Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.


The documentation for this class was generated from the following file: