|
kinematics-dynamics
|
The BasicCartesianControl class implements ICartesianControl.
#include <BasicCartesianControl.hpp>
Classes | |
| class | StateWatcher |
Public Member Functions | |
| bool | stat (std::vector< double > &x, int *state=nullptr, double *timestamp=nullptr) override |
| Current state and position. | |
| bool | inv (const std::vector< double > &xd, std::vector< double > &q) override |
| Inverse kinematics. | |
| bool | movj (const std::vector< double > &xd) override |
| Move in joint space, absolute coordinates. | |
| bool | relj (const std::vector< double > &xd) override |
| Move in joint space, relative coordinates. | |
| bool | movl (const std::vector< double > &xd) override |
| Linear move to target position. | |
| bool | movv (const std::vector< double > &xdotd) override |
| Linear move with given velocity. | |
| bool | gcmp () override |
| Gravity compensation. | |
| bool | forc (const std::vector< double > &fd) override |
| Force control. | |
| bool | stopControl () override |
| Stop control. | |
| bool | wait (double timeout) override |
| Wait until completion. | |
| bool | tool (const std::vector< double > &x) override |
| Change tool. | |
| bool | act (int command) override |
| Actuate tool. | |
| void | pose (const std::vector< double > &x) override |
| Achieve pose. | |
| void | twist (const std::vector< double > &xdot) override |
| Instantaneous velocity steps. | |
| void | wrench (const std::vector< double > &w) override |
| Exert force. | |
| bool | setParameter (int vocab, double value) override |
| Set a configuration parameter. | |
| bool | getParameter (int vocab, double *value) override |
| Retrieve a configuration parameter. | |
| bool | setParameters (const std::map< int, double > ¶ms) override |
| Set multiple configuration parameters. | |
| bool | getParameters (std::map< int, double > ¶ms) override |
| Retrieve multiple configuration parameters. | |
| void | run () override |
| bool | open (yarp::os::Searchable &config) override |
| bool | close () override |
Public Member Functions inherited from roboticslab::ICartesianControl | |
| virtual | ~ICartesianControl ()=default |
| Destructor. | |
Public Member Functions inherited from BasicCartesianControl_ParamsParser | |
| bool | parseParams (const yarp::os::Searchable &config) override |
| std::string | getDeviceClassName () const override |
| std::string | getDeviceName () const override |
| std::string | getDocumentationOfDeviceParams () const override |
| std::vector< std::string > | getListOfParams () const override |
Private Member Functions | |
| int | getCurrentState () const |
| void | setCurrentState (int value) |
| bool | checkJointLimits (const std::vector< double > &q) |
| bool | checkJointLimits (const std::vector< double > &q, const std::vector< double > &qdot) |
| bool | checkJointVelocities (const std::vector< double > &qdot) |
| bool | doFailFastChecks (const std::vector< double > &initialQ) |
| bool | checkControlModes (int mode) |
| bool | setControlModes (int mode) |
| bool | presetStreamingCommand (int command) |
| bool | computeIsocronousSpeeds (const std::vector< double > &q, const std::vector< double > &qd, std::vector< double > &qdot) |
| void | handleMovj (const std::vector< double > &q, const StateWatcher &watcher) |
| void | handleMovlVel (const std::vector< double > &q, const StateWatcher &watcher) |
| void | handleMovlPosd (const std::vector< double > &q, const StateWatcher &watcher) |
| void | handleMovv (const std::vector< double > &q, const StateWatcher &watcher) |
| void | handleGcmp (const std::vector< double > &q, const StateWatcher &watcher) |
| void | handleForc (const std::vector< double > &q, const std::vector< double > &qdot, const std::vector< double > &qdotdot, const StateWatcher &watcher) |
Private Attributes | |
| yarp::dev::PolyDriver | solverDevice |
| roboticslab::ICartesianSolver * | iCartesianSolver {nullptr} |
| yarp::dev::PolyDriver | robotDevice |
| yarp::dev::IControlMode * | iControlMode {nullptr} |
| yarp::dev::IEncoders * | iEncoders {nullptr} |
| yarp::dev::IPositionControl * | iPositionControl {nullptr} |
| yarp::dev::IPositionDirect * | iPositionDirect {nullptr} |
| yarp::dev::IPreciselyTimed * | iPreciselyTimed {nullptr} |
| yarp::dev::ITorqueControl * | iTorqueControl {nullptr} |
| yarp::dev::IVelocityControl * | iVelocityControl {nullptr} |
| roboticslab::ICartesianSolver::reference_frame | referenceFrame |
| int | numJoints {0} |
| int | currentState {VOCAB_CC_NOT_CONTROLLING} |
| int | streamingCommand {VOCAB_CC_NOT_SET} |
| std::mutex | stateMutex |
| std::vector< double > | vmoStored |
| double | movementStartTime {0.0} |
| std::vector< std::unique_ptr< KDL::Trajectory > > | trajectories |
| std::vector< double > | fd |
| int | encoderErrors {0} |
| std::atomic< bool > | cmcSuccess {true} |
| std::vector< double > | qMin |
| std::vector< double > | qMax |
| std::vector< double > | qdotMin |
| std::vector< double > | qdotMax |
| std::vector< double > | qRefSpeeds |
Additional Inherited Members | |
Public Attributes inherited from BasicCartesianControl_ParamsParser | |
| const std::string | m_device_classname = {"BasicCartesianControl"} |
| const std::string | m_device_name = {"BasicCartesianControl"} |
| bool | m_parser_is_strict = false |
| const parser_version_type | m_parser_version = {} |
| const std::string | m_controllerGain_defaultValue = {"0.05"} |
| const std::string | m_trajectoryDuration_defaultValue = {"0.0"} |
| const std::string | m_trajectoryRefSpeed_defaultValue = {"0.05"} |
| const std::string | m_trajectoryRefAccel_defaultValue = {"0.02"} |
| const std::string | m_cmcPeriodMs_defaultValue = {"50"} |
| const std::string | m_waitPeriodMs_defaultValue = {"30"} |
| const std::string | m_usePosdMovl_defaultValue = {"false"} |
| const std::string | m_enableFailFast_defaultValue = {"false"} |
| const std::string | m_referenceFrame_defaultValue = {"base"} |
| const std::string | m_robot_defaultValue = {"remote_controlboard"} |
| const std::string | m_solver_defaultValue = {"KdlSolver"} |
| double | m_controllerGain = {0.05} |
| double | m_trajectoryDuration = {0.0} |
| double | m_trajectoryRefSpeed = {0.05} |
| double | m_trajectoryRefAccel = {0.02} |
| int | m_cmcPeriodMs = {50} |
| int | m_waitPeriodMs = {30} |
| bool | m_usePosdMovl = {false} |
| bool | m_enableFailFast = {false} |
| std::string | m_referenceFrame = {"base"} |
| std::string | m_robot = {"remote_controlboard"} |
| std::string | m_solver = {"KdlSolver"} |
|
overridevirtual |
Send control command to actuate the robot's tool, if available.
| command | One of available actuator vocabs. |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
Enable gravity compensation.
Implements roboticslab::ICartesianControl.
|
overridevirtual |
Ask the controller to retrieve a parameter of 'double' type.
| vocab | YARP-encoded vocab (parameter key). |
| value | Parameter value encoded as a double. |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
Ask the controller to retrieve all available parameters at once.
| params | Dictionary of YARP-encoded vocabs as keys and their values. |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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. |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
Ask the controller to store or update multiple parameters at once.
| params | Dictionary of YARP-encoded vocabs as keys and their values. |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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. |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
Halt current control loop if any and cease movement.
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
Block execution until the movement is completed, errors occur or timeout is reached.
| timeout | Timeout in seconds, '0.0' means no timeout. |
Implements roboticslab::ICartesianControl.
|
overridevirtual |
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). |
Implements roboticslab::ICartesianControl.
|
private |
FORC desired Cartesian force
|
private |
MOVL keep track of movement start time to know at what time of trajectory movement we are
|
private |
MOVL store Cartesian trajectory
|
private |
MOVJ store previous reference speeds