kinematics-dynamics
|
Abstract base class for a cartesian controller.
#include <ICartesianControl.h>
Public Member Functions | |
virtual | ~ICartesianControl ()=default |
Destructor. | |
RPC commands | |
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 | |
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 | |
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 > ¶ms)=0 |
Set multiple configuration parameters. More... | |
virtual bool | getParameters (std::map< int, double > ¶ms)=0 |
Retrieve multiple configuration parameters. More... | |
|
pure virtual |
Send control command to actuate the robot's tool, if available.
command | One of available actuator vocabs. |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Apply desired forces in task space.
fd | 6-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.
|
pure virtual |
Enable gravity compensation.
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Ask the controller to retrieve a parameter of 'double' type.
vocab | YARP-encoded vocab (parameter key). |
value | Parameter value encoded as a double. |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Ask the controller to retrieve all available parameters at once.
params | Dictionary of YARP-encoded vocabs as keys and their values. |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Perform inverse kinematics (using robot position as initial guess), but do not move.
xd | 6-element vector describing desired position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians). |
q | Vector describing current position in joint space (meters or degrees). |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Perform inverse kinematics and move to desired position in joint space using absolute coordinates.
xd | 6-element vector describing desired position 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.
|
pure virtual |
Move to end position along a line trajectory.
xd | 6-element vector describing desired position 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.
|
pure virtual |
Move along a line with constant velocity.
xdotd | 6-element vector describing desired velocity 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.
|
pure virtual |
Move to desired position instantaneously, no further intermediate calculations are expected other than computing the inverse kinematics.
x | 6-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.
|
pure virtual |
Perform inverse kinematics and move to desired position in joint space using relative coordinates.
xd | 6-element vector describing desired offset 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.
|
pure virtual |
Ask the controller to store or update a parameter of 'double' type.
vocab | YARP-encoded vocab (parameter key). |
value | Parameter value encoded as a double. |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Ask the controller to store or update multiple parameters at once.
params | Dictionary of YARP-encoded vocabs as keys and their values. |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Inform on control state, get robot position and perform forward kinematics.
x | 6-element vector describing current position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians). |
state | Identifier for a cartesian control vocab. |
timestamp | Remote encoder acquisition time. |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Halt current control loop if any and cease movement.
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Unload current tool if any and append new tool frame to the kinematic chain.
x | 6-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). |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Move in instantaneous velocity increments.
xdot | 6-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.
|
pure virtual |
Block execution until the movement is completed, errors occur or timeout is reached.
timeout | Timeout in seconds, '0.0' means no timeout. |
Implemented in roboticslab::CartesianControlClient, and roboticslab::BasicCartesianControl.
|
pure virtual |
Make the TCP exert the desired force instantaneously.
w | 6-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.