Visual Servoing Platform
version 3.6.1 under development (2024-11-15)
|
#include <visp3/robot/vpRobotUniversalRobots.h>
Public Types | |
enum | vpRobotStateType { STATE_STOP , STATE_VELOCITY_CONTROL , STATE_POSITION_CONTROL , STATE_ACCELERATION_CONTROL , STATE_FORCE_TORQUE_CONTROL } |
enum | vpControlFrameType { REFERENCE_FRAME , ARTICULAR_FRAME , JOINT_STATE = ARTICULAR_FRAME , END_EFFECTOR_FRAME , CAMERA_FRAME , TOOL_FRAME = CAMERA_FRAME , MIXT_FRAME } |
Public Member Functions | |
vpRobotUniversalRobots () | |
vpRobotUniversalRobots (const std::string &ur_address) | |
virtual | ~vpRobotUniversalRobots () |
void | connect (const std::string &ur_address) |
void | disconnect () |
std::shared_ptr< ur_rtde::RTDEReceiveInterface > | getRTDEReceiveInterfaceHandler () const |
std::shared_ptr< ur_rtde::RTDEControlInterface > | getRTDEControlInterfaceHandler () const |
std::shared_ptr< ur_rtde::DashboardClient > | getDashboardClientHandler () const |
vpHomogeneousMatrix | get_fMe () |
vpHomogeneousMatrix | get_fMe (const vpColVector &q) |
vpHomogeneousMatrix | get_fMc () |
vpHomogeneousMatrix | get_eMc () const |
void | getForceTorque (const vpRobot::vpControlFrameType frame, vpColVector &force) |
std::string | getPolyScopeVersion () |
void | getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE |
void | getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &pose) |
int | getRobotMode () const |
std::string | getRobotModel () const |
void | move (const std::string &filename, double velocity_percentage=10.) |
bool | readPosFile (const std::string &filename, vpColVector &q) |
bool | savePosFile (const std::string &filename, const vpColVector &q) |
void | setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE |
void | setPosition (const vpRobot::vpControlFrameType frame, const vpPoseVector &pose) |
void | setPositioningVelocity (double velocity) |
vpRobot::vpRobotStateType | setRobotState (vpRobot::vpRobotStateType newState) |
void | setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE |
void | set_eMc (const vpHomogeneousMatrix &eMc) |
void | stopMotion () |
Inherited functionalities from vpRobot | |
double | getMaxTranslationVelocity (void) const |
double | getMaxRotationVelocity (void) const |
int | getNDof () const |
vpColVector | getPosition (const vpRobot::vpControlFrameType frame) |
virtual vpRobotStateType | getRobotState (void) const |
void | setMaxRotationVelocity (double maxVr) |
void | setMaxTranslationVelocity (double maxVt) |
void | setVerbose (bool verbose) |
Static Public Member Functions | |
Static Public Member Functions inherited from vpRobot | |
static vpColVector | saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false) |
Protected Member Functions | |
void | init () |
Protected Member Functions Inherited from vpRobot | |
vpControlFrameType | setRobotFrame (vpRobot::vpControlFrameType newFrame) |
vpControlFrameType | getRobotFrame (void) const |
Protected Attributes | |
std::shared_ptr< ur_rtde::RTDEReceiveInterface > | m_rtde_receive |
std::shared_ptr< ur_rtde::RTDEControlInterface > | m_rtde_control |
std::shared_ptr< ur_rtde::DashboardClient > | m_db_client |
vpHomogeneousMatrix | m_eMc |
double | m_positioningVelocity |
double | m_max_joint_speed |
double | m_max_joint_acceleration |
double | m_max_linear_speed |
double | m_max_linear_acceleration |
vpRobot::vpControlFrameType | m_vel_control_frame |
double | maxTranslationVelocity |
double | maxRotationVelocity |
int | nDof |
vpMatrix | eJe |
int | eJeAvailable |
vpMatrix | fJe |
int | fJeAvailable |
int | areJointLimitsAvailable |
double * | qmin |
double * | qmax |
bool | verbose_ |
Static Protected Attributes | |
static const double | maxTranslationVelocityDefault = 0.2 |
static const double | maxRotationVelocityDefault = 0.7 |
Definition at line 61 of file vpRobotUniversalRobots.h.
|
inherited |
Robot control frames.
Enumerator | |
---|---|
REFERENCE_FRAME | Corresponds to a fixed reference frame attached to the robot structure. |
ARTICULAR_FRAME | Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE. |
JOINT_STATE | Corresponds to the joint state. |
END_EFFECTOR_FRAME | Corresponds to robot end-effector frame. |
CAMERA_FRAME | Corresponds to a frame attached to the camera mounted on the robot end-effector. |
TOOL_FRAME | Corresponds to a frame attached to the tool (camera, gripper...) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME. |
MIXT_FRAME | Corresponds to a "virtual" frame where translations are expressed in the reference frame, and rotations in the camera frame. |
|
inherited |
Robot control states.
BEGIN_VISP_NAMESPACE vpRobotUniversalRobots::vpRobotUniversalRobots | ( | ) |
Default constructor.
Definition at line 51 of file vpRobotUniversalRobots.cpp.
References init().
vpRobotUniversalRobots::vpRobotUniversalRobots | ( | const std::string & | ur_address | ) |
Establishes a connection with the robot and
[in] | ur_address | IP/hostname of the robot. |
Definition at line 69 of file vpRobotUniversalRobots.cpp.
|
virtual |
Destructor that shut down the connexion with the robot.
Definition at line 59 of file vpRobotUniversalRobots.cpp.
References setRobotState(), and vpRobot::STATE_STOP.
void vpRobotUniversalRobots::connect | ( | const std::string & | ur_address | ) |
Establishes a connection with the robot and set default behavior.
[in] | ur_address | IP/hostname of the robot. |
vpException::fatalError | : When connexion cannot be established. |
Definition at line 82 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, m_db_client, m_rtde_control, and m_rtde_receive.
Referenced by vpRobotUniversalRobots().
void vpRobotUniversalRobots::disconnect | ( | ) |
Disconnect the robot interfaces.
Definition at line 116 of file vpRobotUniversalRobots.cpp.
References m_db_client, m_rtde_control, and m_rtde_receive.
vpHomogeneousMatrix vpRobotUniversalRobots::get_eMc | ( | ) | const |
Return the homogeneous transformation that gives the position of the camera frame (or in general of any tool frame) in the robot end-effector frame.
By default, this transformation is set to identity, meaning that the camera (or tool) frame is located on the end-effector.
To change the position of the camera (or tool) frame on the end-effector frame, use set_eMc().
Definition at line 244 of file vpRobotUniversalRobots.cpp.
References m_eMc.
Referenced by getForceTorque().
vpHomogeneousMatrix vpRobotUniversalRobots::get_fMc | ( | ) |
Given the current joint position of the robot, computes the forward kinematics (direct geometric model) as an homogeneous matrix that gives the position of the camera frame (or in general of any tool attached to the robot) in the robot base frame.
By default, the transformation that corresponds to the transformation between the end-effector and the camera (or tool) frame is set to identity, meaning that the camera (or tool) frame is located on the end-effector.
To change the position of the camera (or tool) frame, use set_eMc().
Definition at line 213 of file vpRobotUniversalRobots.cpp.
References vpRobot::CAMERA_FRAME, and getPosition().
vpHomogeneousMatrix vpRobotUniversalRobots::get_fMe | ( | ) |
Given the current joint position of the robot, computes the forward kinematics (direct geometric model) as an homogeneous matrix that gives the position of the end-effector in the robot base frame.
As described here the end-effector position could be modified setting the Tool Center Point (TCP). When TCP translations and rotations are set to 0, the end-effector corresponds to the robot flange position.
Definition at line 154 of file vpRobotUniversalRobots.cpp.
References vpRobot::END_EFFECTOR_FRAME, and getPosition().
Referenced by setVelocity().
vpHomogeneousMatrix vpRobotUniversalRobots::get_fMe | ( | const vpColVector & | q | ) |
Given a joint position of the robot, computes the forward kinematics (direct geometric model) as an homogeneous matrix that gives the position of the end-effector in the robot base frame.
As described here the end-effector position could be modified setting the Tool Center Point (TCP). When TCP translations and rotations are set to 0, the end-effector corresponds to the robot flange position.
[in] | q | : Joint position as a 6-dim vector |
Definition at line 174 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, m_rtde_control, m_rtde_receive, vpArray2D< Type >::size(), and vpColVector::toStdVector().
|
inline |
Return handler to DashboardClient.
Definition at line 90 of file vpRobotUniversalRobots.h.
void vpRobotUniversalRobots::getForceTorque | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | force | ||
) |
Get robot force torque.
[in] | frame | : Type of forces and torques to retrieve. Admissible values are:
|
[out] | force | : Measured forced and torques. |
Definition at line 255 of file vpRobotUniversalRobots.cpp.
References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, get_eMc(), vpHomogeneousMatrix::inverse(), vpRobot::JOINT_STATE, m_rtde_receive, and vpRobot::TOOL_FRAME.
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 274 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 252 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inlineinherited |
Return robot degrees of freedom number.
std::string vpRobotUniversalRobots::getPolyScopeVersion | ( | ) |
Return PolyScope version.
Definition at line 288 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, and m_db_client.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 217 of file vpRobot.cpp.
References vpRobot::getPosition().
|
virtual |
Get robot position.
[in] | frame | : Type of position to retrieve. Admissible values are:
|
[out] | position | : Robot position. When joint position is asked this vector is 6-dim. Otherwise for a cartesian position this vector is also 6-dim. Its content is similar to a vpPoseVector, with first the 3 tranlations in meter and then the 3 orientations in radian as a vector (see vpThetaUVector). |
If you want to get a cartesian position, use rather getPosition(const vpRobot::vpControlFrameType, vpPoseVector &)
Implements vpRobot.
Definition at line 310 of file vpRobotUniversalRobots.cpp.
References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, vpRobot::JOINT_STATE, m_eMc, m_rtde_receive, vpColVector::resize(), and vpRobot::TOOL_FRAME.
Referenced by get_fMc(), get_fMe(), and getPosition().
void vpRobotUniversalRobots::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | pose | ||
) |
Get robot cartesian position.
[in] | frame | : Type of cartesian position to retrieve. Admissible values are:
|
[out] | pose | : Robot cartesian position. This vector is 6-dim with first the 3 tranlations in meter and then the 3 orientations in radian as a vector (see vpThetaUVector). |
Definition at line 366 of file vpRobotUniversalRobots.cpp.
References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, getPosition(), vpRobot::JOINT_STATE, m_rtde_receive, and vpRobot::TOOL_FRAME.
|
inlineprotectedinherited |
int vpRobotUniversalRobots::getRobotMode | ( | ) | const |
Get and return robot mode. Available robot modes are described here.
Definition at line 405 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, and m_rtde_receive.
std::string vpRobotUniversalRobots::getRobotModel | ( | ) | const |
Get and return robot model as a string like "UR5", "UR10"...
Definition at line 394 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, and m_db_client.
|
inlinevirtualinherited |
Definition at line 155 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotBiclops::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotBiclops::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
|
inline |
Return handler to RTDEControlInterface.
Definition at line 85 of file vpRobotUniversalRobots.h.
|
inline |
Return handler to RTDEReceiveInterface.
Definition at line 80 of file vpRobotUniversalRobots.h.
|
protectedvirtual |
Initialize internal vars.
Implements vpRobot.
Definition at line 132 of file vpRobotUniversalRobots.cpp.
References vpRobot::JOINT_STATE, m_max_joint_acceleration, m_max_joint_speed, m_max_linear_acceleration, m_max_linear_speed, m_positioningVelocity, m_vel_control_frame, vpRobot::nDof, and vpMath::rad().
Referenced by vpRobotUniversalRobots().
void vpRobotUniversalRobots::move | ( | const std::string & | filename, |
double | velocity_percentage = 10. |
||
) |
Moves the robot to the joint position specified in the filename. The positioning velocity is set to 10% of the robot maximal velocity.
[in] | filename | : File containing a joint position to reach. |
[in] | velocity_percentage | : Velocity percentage. Values in range [1, 100]. |
Definition at line 691 of file vpRobotUniversalRobots.cpp.
References vpRobot::JOINT_STATE, readPosFile(), setPosition(), setPositioningVelocity(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
bool vpRobotUniversalRobots::readPosFile | ( | const std::string & | filename, |
vpColVector & | q | ||
) |
Read joint positions in a specific Franka position file.
This position file has to start with a header. The seven joint positions are given after the "R:" keyword and are expressed in degres to be more representative for the user. Theses values are then converted in radians in q. The character "#" starting a line indicates a comment.
A typical content of such a file is given below:
[in] | filename | : Name of the position file to read. |
[out] | q | : 6-dim joint positions: q1 q2 q3 q4 q5 q6 with values expressed in radians. |
The code below shows how to read a position from a file and move the robot to this position.
Definition at line 738 of file vpRobotUniversalRobots.cpp.
References vpRobot::nDof, vpMath::rad(), vpColVector::resize(), and vpIoTools::splitChain().
Referenced by move().
|
staticinherited |
Saturate velocities.
v_in | : Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s. |
v_max | : Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s. |
verbose | : Print a message indicating which axis causes the saturation. |
vpRobotException::dimensionError | : If the input vectors have different dimensions. |
The code below shows how to use this static method in order to saturate a velocity skew vector.
Definition at line 164 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
bool vpRobotUniversalRobots::savePosFile | ( | const std::string & | filename, |
const vpColVector & | q | ||
) |
Save joint positions in a specific Panda position file.
This position file starts with a header on the first line. After convertion of the rotations in degrees, the joint position q is written on a line starting with the keyword "R: ". See readPosFile() documentation for an example of such a file.
[in] | filename | : Name of the position file to create. |
[in] | q | : Joint positions vector to save in the filename with values expressed in radians. |
Definition at line 816 of file vpRobotUniversalRobots.cpp.
References vpMath::deg().
void vpRobotUniversalRobots::set_eMc | ( | const vpHomogeneousMatrix & | eMc | ) |
Set the homogeneous transformation that gives the position of the camera frame (or in general of any tool frame) in the robot end-effector frame.
By default, this transformation is set to identity, meaning that the camera (or tool) frame is located on the end-effector.
This transformation has to be set before controlling the robot cartesian velocity in the camera frame or getting the position of the robot in the camera frame.
[in] | eMc | : End-effector to camera frame transformation. |
Definition at line 232 of file vpRobotUniversalRobots.cpp.
References m_eMc.
|
inherited |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
w_max | : Maximum rotational velocity expressed in rad/s. |
Definition at line 261 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotViper650::setMaxRotationVelocity(), and vpRobotViper850::setMaxRotationVelocity().
|
inherited |
Set the maximal translation velocity that can be sent to the robot during a velocity control.
v_max | : Maximum translation velocity expressed in m/s. |
Definition at line 240 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
|
virtual |
Set robot position. This function is blocking; it returns when the desired position is reached.
[in] | position | : A 6-dim vector vector corresponding to the position to reach. All the positions are expressed in meters for the translations and radians for the rotations. |
[in] | frame | : Frame in which the position is expressed.
|
Implements vpRobot.
Definition at line 458 of file vpRobotUniversalRobots.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpColVector::extract(), vpException::fatalError, vpException::functionNotImplementedError, vpRobot::getRobotState(), vpHomogeneousMatrix::inverse(), vpRobot::JOINT_STATE, m_eMc, m_max_joint_speed, m_max_linear_speed, m_positioningVelocity, m_rtde_control, m_rtde_receive, setRobotState(), vpArray2D< Type >::size(), vpRobot::STATE_POSITION_CONTROL, vpColVector::toStdVector(), and vpPoseVector::toStdVector().
Referenced by move(), and setPosition().
void vpRobotUniversalRobots::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
const vpPoseVector & | pose | ||
) |
Set robot cartesian position. This function is blocking; it returns when the desired position is reached.
[in] | pose | : A 6-dim vector vector corresponding to the position to reach. All the positions are expressed in meters for the translations and radians for the rotations. |
[in] | frame | : Frame in which the position is expressed.
|
Definition at line 435 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, vpRobot::JOINT_STATE, and setPosition().
void vpRobotUniversalRobots::setPositioningVelocity | ( | double | velocity | ) |
Set the maximal velocity percentage to use for a position control.
[in] | velocity | : Percentage of the maximal velocity. Values should be in ]0:100]. |
Definition at line 420 of file vpRobotUniversalRobots.cpp.
References m_positioningVelocity.
Referenced by move().
|
protectedinherited |
Definition at line 208 of file vpRobot.cpp.
Referenced by vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
virtual |
Change the robot state.
[in] | newState | : New requested robot state. |
Reimplemented from vpRobot.
Definition at line 843 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, vpRobot::getRobotState(), m_rtde_control, vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.
Referenced by move(), setPosition(), stopMotion(), and ~vpRobotUniversalRobots().
|
virtual |
Apply a velocity to the robot.
[in] | frame | : Control frame in which the velocity is expressed. Velocities could be expressed in joint state, robot base frame, end-effector frame or camera frame. |
[in] | vel | : Velocity vector. Translation velocities are expressed in m/s while rotation velocities in rad/s. The size of this vector is always 6. |
frame
should be set to vpRobot::REFERENCE_FRAME, is a velocity twist vector corresponding to the velocity of the origin of the end-effector frame expressed in the reference frame, with translations velocities in m/s and rotation velocities in rad/s.vpRobotException::wrongStateError | : If a the robot is not configured to handle a velocity. The robot can handle a velocity only if the velocity control mode is set. For that, call setRobotState( vpRobot::STATE_VELOCITY_CONTROL) before setVelocity(). |
Implements vpRobot.
Definition at line 602 of file vpRobotUniversalRobots.cpp.
References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpException::functionNotImplementedError, get_fMe(), vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpRobot::JOINT_STATE, m_eMc, m_rtde_control, m_vel_control_frame, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::STATE_VELOCITY_CONTROL, vpColVector::toStdVector(), and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 170 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
void vpRobotUniversalRobots::stopMotion | ( | void | ) |
Stop the robot when it is controlled in velocity and set the robot state to vpRobot::STATE_STOP.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot stopping. |
Definition at line 674 of file vpRobotUniversalRobots.cpp.
References vpException::fatalError, m_rtde_control, setRobotState(), and vpRobot::STATE_STOP.
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 106 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), vpRobotAfma6::get_eJe(), vpRobotPtu46::get_eJe(), vpRobotAfma4::get_eJe(), vpRobotBiclops::get_eJe(), vpRobotKinova::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobot::operator=(), and vpRobotAfma4::setVelocity().
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 108 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 110 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_fJe(), vpRobotAfma6::get_fJe(), vpRobotPtu46::get_fJe(), vpRobotAfma4::get_fJe(), vpRobotBiclops::get_fJe(), vpRobotKinova::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), and vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protected |
Definition at line 131 of file vpRobotUniversalRobots.h.
Referenced by connect(), disconnect(), getPolyScopeVersion(), and getRobotModel().
|
protected |
Definition at line 132 of file vpRobotUniversalRobots.h.
Referenced by get_eMc(), getPosition(), set_eMc(), setPosition(), and setVelocity().
|
protected |
Definition at line 135 of file vpRobotUniversalRobots.h.
Referenced by init().
|
protected |
Definition at line 134 of file vpRobotUniversalRobots.h.
Referenced by init(), and setPosition().
|
protected |
Definition at line 137 of file vpRobotUniversalRobots.h.
Referenced by init().
|
protected |
Definition at line 136 of file vpRobotUniversalRobots.h.
Referenced by init(), and setPosition().
|
protected |
Definition at line 133 of file vpRobotUniversalRobots.h.
Referenced by init(), setPosition(), and setPositioningVelocity().
|
protected |
Definition at line 130 of file vpRobotUniversalRobots.h.
Referenced by connect(), disconnect(), get_fMe(), setPosition(), setRobotState(), setVelocity(), and stopMotion().
|
protected |
Definition at line 129 of file vpRobotUniversalRobots.h.
Referenced by connect(), disconnect(), get_fMe(), getForceTorque(), getPosition(), getRobotMode(), and setPosition().
|
protected |
Definition at line 138 of file vpRobotUniversalRobots.h.
Referenced by init(), and setVelocity().
|
protectedinherited |
Definition at line 100 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 101 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
number of degrees of freedom
Definition at line 104 of file vpRobot.h.
Referenced by vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_fJe(), vpRobotKinova::getJointPosition(), vpRobotPololuPtu::getPosition(), vpRobotFlirPtu::init(), vpRobotKinova::init(), init(), vpRobotTemplate::init(), vpRobot::operator=(), readPosFile(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), and vpRobotPololuPtu::vpRobotPololuPtu().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 115 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 118 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), vpRobotAfma6::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().