Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
vpRobotUniversalRobots Class Reference

#include <visp3/robot/vpRobotUniversalRobots.h>

+ Inheritance diagram for vpRobotUniversalRobots:

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
 

Detailed Description

Member Enumeration Documentation

◆ vpControlFrameType

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.

Definition at line 76 of file vpRobot.h.

◆ vpRobotStateType

enum vpRobot::vpRobotStateType
inherited

Robot control states.

Enumerator
STATE_STOP 

Stops robot motion especially in velocity and acceleration control.

STATE_VELOCITY_CONTROL 

Initialize the velocity controller.

STATE_POSITION_CONTROL 

Initialize the position controller.

STATE_ACCELERATION_CONTROL 

Initialize the acceleration controller.

STATE_FORCE_TORQUE_CONTROL 

Initialize the force/torque controller.

Definition at line 64 of file vpRobot.h.

Constructor & Destructor Documentation

◆ vpRobotUniversalRobots() [1/2]

BEGIN_VISP_NAMESPACE vpRobotUniversalRobots::vpRobotUniversalRobots ( )

Default constructor.

  • set eMc transformation to eye()
  • set default positioning velocity to 20% of the max joint speed
  • set max joint speed to 180 deg/s
  • set max joint acceleration to 800 deg/s^2

Definition at line 51 of file vpRobotUniversalRobots.cpp.

References init().

◆ vpRobotUniversalRobots() [2/2]

vpRobotUniversalRobots::vpRobotUniversalRobots ( const std::string &  ur_address)

Establishes a connection with the robot and

  • set eMc transformation to eye()
  • set default positioning velocity to 20% of the max joint speed
  • set max joint speed to 180 deg/s
  • set max linear speed to 0.5 m/s
    Parameters
    [in]ur_addressIP/hostname of the robot.

Definition at line 69 of file vpRobotUniversalRobots.cpp.

References connect(), and init().

◆ ~vpRobotUniversalRobots()

vpRobotUniversalRobots::~vpRobotUniversalRobots ( )
virtual

Destructor that shut down the connexion with the robot.

Definition at line 59 of file vpRobotUniversalRobots.cpp.

References setRobotState(), and vpRobot::STATE_STOP.

Member Function Documentation

◆ connect()

void vpRobotUniversalRobots::connect ( const std::string &  ur_address)

Establishes a connection with the robot and set default behavior.

Parameters
[in]ur_addressIP/hostname of the robot.
Exceptions
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().

◆ disconnect()

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.

◆ get_eMc()

vpHomogeneousMatrix vpRobotUniversalRobots::get_eMc ( ) const

Return the $ ^{e}{\bf M}_c$ 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().

◆ get_fMc()

vpHomogeneousMatrix vpRobotUniversalRobots::get_fMc ( )

Given the current joint position of the robot, computes the forward kinematics (direct geometric model) as an homogeneous matrix ${^f}{\bf M}_c$ 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 $^{e}{\bf M}_c$ 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().

Returns
Position of the camera frame (or tool frame) in the robot base frame.

Definition at line 213 of file vpRobotUniversalRobots.cpp.

References vpRobot::CAMERA_FRAME, and getPosition().

◆ get_fMe() [1/2]

vpHomogeneousMatrix vpRobotUniversalRobots::get_fMe ( )

Given the current joint position of the robot, computes the forward kinematics (direct geometric model) as an homogeneous matrix ${^f}{\bf M}_e$ 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.

Returns
Position of the end-effector in the robot base frame.

Definition at line 154 of file vpRobotUniversalRobots.cpp.

References vpRobot::END_EFFECTOR_FRAME, and getPosition().

Referenced by setVelocity().

◆ get_fMe() [2/2]

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 ${^f}{\bf M}_e$ 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.

Parameters
[in]q: Joint position as a 6-dim vector
Returns
Position of the end-effector in the robot base frame.

Definition at line 174 of file vpRobotUniversalRobots.cpp.

References vpException::fatalError, m_rtde_control, m_rtde_receive, vpArray2D< Type >::size(), and vpColVector::toStdVector().

◆ getDashboardClientHandler()

std::shared_ptr<ur_rtde::DashboardClient> vpRobotUniversalRobots::getDashboardClientHandler ( ) const
inline

Return handler to DashboardClient.

Definition at line 90 of file vpRobotUniversalRobots.h.

◆ getForceTorque()

void vpRobotUniversalRobots::getForceTorque ( const vpRobot::vpControlFrameType  frame,
vpColVector force 
)

Get robot force torque.

Parameters
[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.

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

double vpRobot::getMaxTranslationVelocity ( void  ) const
inherited

◆ getNDof()

int vpRobot::getNDof ( ) const
inlineinherited

Return robot degrees of freedom number.

Examples
servoPololuPtuPoint2DJointVelocity.cpp.

Definition at line 145 of file vpRobot.h.

◆ getPolyScopeVersion()

std::string vpRobotUniversalRobots::getPolyScopeVersion ( )

Return PolyScope version.

Definition at line 288 of file vpRobotUniversalRobots.cpp.

References vpException::fatalError, and m_db_client.

◆ getPosition() [1/3]

vpColVector vpRobot::getPosition ( const vpRobot::vpControlFrameType  frame)
inherited

Return the current robot position in the specified frame.

Definition at line 217 of file vpRobot.cpp.

References vpRobot::getPosition().

◆ getPosition() [2/3]

void vpRobotUniversalRobots::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector position 
)
virtual

Get robot position.

Parameters
[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 $\theta {\bf u}$ 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().

◆ getPosition() [3/3]

void vpRobotUniversalRobots::getPosition ( const vpRobot::vpControlFrameType  frame,
vpPoseVector pose 
)

Get robot cartesian position.

Parameters
[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 $\theta {\bf u}$ 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.

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited

Definition at line 183 of file vpRobot.h.

◆ getRobotMode()

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.

◆ getRobotModel()

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.

◆ getRobotState()

◆ getRTDEControlInterfaceHandler()

std::shared_ptr<ur_rtde::RTDEControlInterface> vpRobotUniversalRobots::getRTDEControlInterfaceHandler ( ) const
inline

Return handler to RTDEControlInterface.

Definition at line 85 of file vpRobotUniversalRobots.h.

◆ getRTDEReceiveInterfaceHandler()

std::shared_ptr<ur_rtde::RTDEReceiveInterface> vpRobotUniversalRobots::getRTDEReceiveInterfaceHandler ( ) const
inline

Return handler to RTDEReceiveInterface.

Definition at line 80 of file vpRobotUniversalRobots.h.

◆ init()

void vpRobotUniversalRobots::init ( void  )
protectedvirtual

◆ move()

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.

Parameters
[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.

◆ readPosFile()

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:

#UR - Joint position file
#
# R: q1 q2 q3 q4 q5 q6
# with joint positions q1 to q6 expressed in degrees
#
R: 0.1 0.3 -0.25 -80.5 80 0
Parameters
[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.
Returns
true if the positions were successfully read from the file, false otherwise.

The code below shows how to read a position from a file and move the robot to this position.

vpColVector q; // Joint position
robot.readPosFile("myposition.pos", q); // Set the joint position from the file
robot.setPositioningVelocity(5); // Positioning velocity set to 5%
robot.setPosition(vpRobot::JOINT_STATE, q); // Move to the joint position
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
@ JOINT_STATE
Definition: vpRobot.h:82
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
See also
savePosFile(), move()

Definition at line 738 of file vpRobotUniversalRobots.cpp.

References vpRobot::nDof, vpMath::rad(), vpColVector::resize(), and vpIoTools::splitChain().

Referenced by move().

◆ saturateVelocities()

vpColVector vpRobot::saturateVelocities ( const vpColVector v_in,
const vpColVector v_max,
bool  verbose = false 
)
staticinherited

Saturate velocities.

Parameters
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.
Returns
Saturated velocities.
Exceptions
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.

#include <iostream>
#include <visp3/robot/vpRobot.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
// Set a velocity skew vector
v[0] = 0.1; // vx in m/s
v[1] = 0.2; // vy
v[2] = 0.3; // vz
v[3] = vpMath::rad(10); // wx in rad/s
v[4] = vpMath::rad(-10); // wy
v[5] = vpMath::rad(20); // wz
// Set the maximal allowed velocities
vpColVector v_max(6);
for (int i=0; i<3; i++)
v_max[i] = 0.3; // in translation (m/s)
for (int i=3; i<6; i++)
v_max[i] = vpMath::rad(10); // in rotation (rad/s)
// Compute the saturated velocity skew vector
vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
std::cout << "v : " << v.t() << std::endl;
std::cout << "v max: " << v_max.t() << std::endl;
std::cout << "v sat: " << v_sat.t() << std::endl;
return 0;
}
vpRowVector t() const
static double rad(double deg)
Definition: vpMath.h:129
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164

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().

◆ savePosFile()

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.

Parameters
[in]filename: Name of the position file to create.
[in]q: Joint positions vector to save in the filename with values expressed in radians.
Warning
The joint rotations written in the file are converted in degrees to be more representative for the user.
Returns
true if the positions were successfully saved in the file. false, if an error occurs.
See also
readPosFile()

Definition at line 816 of file vpRobotUniversalRobots.cpp.

References vpMath::deg().

◆ set_eMc()

void vpRobotUniversalRobots::set_eMc ( const vpHomogeneousMatrix eMc)

Set the $ ^{e}{\bf M}_c$ 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.

Parameters
[in]eMc: End-effector to camera frame transformation.

Definition at line 232 of file vpRobotUniversalRobots.cpp.

References m_eMc.

◆ setMaxRotationVelocity()

void vpRobot::setMaxRotationVelocity ( double  w_max)
inherited

Set the maximal rotation velocity that can be sent to the robot during a velocity control.

Parameters
w_max: Maximum rotational velocity expressed in rad/s.
Examples
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, testFeatureSegment.cpp, testFrankaJointVelocityLimits.cpp, and testRobotFlirPtu.cpp.

Definition at line 261 of file vpRobot.cpp.

References vpRobot::maxRotationVelocity.

Referenced by vpRobotViper650::setMaxRotationVelocity(), and vpRobotViper850::setMaxRotationVelocity().

◆ setMaxTranslationVelocity()

void vpRobot::setMaxTranslationVelocity ( double  v_max)
inherited

Set the maximal translation velocity that can be sent to the robot during a velocity control.

Parameters
v_max: Maximum translation velocity expressed in m/s.
Examples
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, and testFeatureSegment.cpp.

Definition at line 240 of file vpRobot.cpp.

References vpRobot::maxTranslationVelocity.

◆ setPosition() [1/2]

void vpRobotUniversalRobots::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector position 
)
virtual

Set robot position. This function is blocking; it returns when the desired position is reached.

Parameters
[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.
  • In the joint space, positions are the six joint positions.
  • In the camera frame (or the tool frame which is the same), the 3 first vector values correspond to the translation between the robot base and the camera (or tool frame), while the 3 last vector values to the ThetaU rotations represented by a vpThetaUVector.
  • In the end-effector frame (or TCP frame), the 3 first vector values correspond to the translation between the robot base and the end-effector, while the 3 last vector values to the ThetaU rotations represented by a vpThetaUVector.

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().

◆ setPosition() [2/2]

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.

Parameters
[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.
  • In the camera frame (or the tool frame which is the same), the 3 first vector values correspond to the translation between the robot base and the camera (or tool frame), while the 3 last vector values to the ThetaU rotations represented by a vpThetaUVector.
  • In the end-effector frame (or TCP frame), the 3 first vector values correspond to the translation between the robot base and the end-effector, while the 3 last vector values to the ThetaU rotations represented by a vpThetaUVector.

Definition at line 435 of file vpRobotUniversalRobots.cpp.

References vpException::fatalError, vpRobot::JOINT_STATE, and setPosition().

◆ setPositioningVelocity()

void vpRobotUniversalRobots::setPositioningVelocity ( double  velocity)

Set the maximal velocity percentage to use for a position control.

Parameters
[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().

◆ setRobotFrame()

vpRobot::vpControlFrameType vpRobot::setRobotFrame ( vpRobot::vpControlFrameType  newFrame)
protectedinherited

◆ setRobotState()

vpRobot::vpRobotStateType vpRobotUniversalRobots::setRobotState ( vpRobot::vpRobotStateType  newState)
virtual

Change the robot state.

Parameters
[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().

◆ setVelocity()

void vpRobotUniversalRobots::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector vel 
)
virtual

Apply a velocity to the robot.

Parameters
[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.
  • In joint state, $ vel = [\dot{q}_1, \dot{q}_2, \dot{q}_3, \dot{q}_4, \dot{q}_5, \dot{q}_6]^t $ correspond to joint velocities in rad/s.
  • When cartesian velocities have to be applied in the reference frame corresponding to the robot base frame, frame should be set to vpRobot::REFERENCE_FRAME, $ vel = [^{f} v_x, ^{f} v_y, ^{f} v_z, ^{f} \omega_x, ^{f} \omega_y, ^{f} \omega_z]^T $ 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 $ ^{f} v_x, ^{f} v_y, ^{f} v_z $ in m/s and rotation velocities $ ^{f}\omega_x, ^{f} \omega_y, ^{f} \omega_z $ in rad/s.
  • When cartesian velocities have to be applied in the end-effector frame, frame should be set to vpRobot::END_EFFECTOR_FRAME, $ vel = [^{e} v_x, ^{e} v_y, ^{e} v_z, ^{e} \omega_x, ^{e} \omega_y, ^{e} \omega_z]^T $ is a velocity twist vector corresponding to the velocity of the origin of the end-effector frame expressed in the end-effector frame, with translations velocities $ ^{e} v_x, ^{e} v_y, ^{e} v_z $ in m/s and rotation velocities $ ^{e}\omega_x, ^{e} \omega_y, ^{e} \omega_z $ in rad/s.
  • When cartesian velocities have to be applied in the camera frame or more generally in a tool frame, frame should be set to vpRobot::CAMERA_FRAME or vpRobot::TOOL_FRAME (which are equivalent in ViSP), $ vel = [^{c} v_x, ^{c} v_y, ^{c} v_z, ^{c} \omega_x, ^{c} \omega_y, ^{c} \omega_z]^T $ is a velocity twist vector corresponding to the velocity of the origin of the camera (or tool frame) frame expressed in the camera (or tool frame), with translations velocities $ ^{c} v_x, ^{c} v_y, ^{c} v_z $ in m/s and rotation velocities $ ^{c}\omega_x, ^{c} \omega_y, ^{c} \omega_z $ in rad/s. The position of the camera frame could be set using set_eMc().
Exceptions
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().
Warning
Velocities could be saturated if one of them exceed the maximal authorized speed (see vpRobot::maxTranslationVelocity and vpRobot::maxRotationVelocity). To change these values use setMaxTranslationVelocity() and setMaxRotationVelocity().
#include <visp3/core/vpColVector.h>
#include <visp3/core/vpMath.h>
#include <visp3/robot/vpRobotUniversalRobots.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
#if defined(VISP_HAVE_UR_RTDE)
vpColVector qd(6);
// Set a joint velocity
qd[0] = 0.1; // Joint 1 velocity in rad/s
qd[1] = vpMath::rad(15); // Joint 2 velocity in rad/s
qd[2] = 0; // Joint 3 velocity in rad/s
qd[3] = M_PI/8; // Joint 4 velocity in rad/s
qd[4] = 0; // Joint 5 velocity in rad/s
qd[5] = 0; // Joint 6 velocity in rad/s
// Initialize the controller to velocity control
while (1) {
// Apply a velocity in the joint space
// Compute new velocities qvel...
}
// Stop the robot
#endif
}
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66

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.

◆ setVerbose()

◆ stopMotion()

void vpRobotUniversalRobots::stopMotion ( void  )

Stop the robot when it is controlled in velocity and set the robot state to vpRobot::STATE_STOP.

Exceptions
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.

Member Data Documentation

◆ areJointLimitsAvailable

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 114 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ eJe

◆ eJeAvailable

int vpRobot::eJeAvailable
protectedinherited

is the robot Jacobian expressed in the end-effector frame available

Definition at line 108 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ fJe

◆ fJeAvailable

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 112 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ m_db_client

std::shared_ptr<ur_rtde::DashboardClient> vpRobotUniversalRobots::m_db_client
protected

Definition at line 131 of file vpRobotUniversalRobots.h.

Referenced by connect(), disconnect(), getPolyScopeVersion(), and getRobotModel().

◆ m_eMc

vpHomogeneousMatrix vpRobotUniversalRobots::m_eMc
protected

Definition at line 132 of file vpRobotUniversalRobots.h.

Referenced by get_eMc(), getPosition(), set_eMc(), setPosition(), and setVelocity().

◆ m_max_joint_acceleration

double vpRobotUniversalRobots::m_max_joint_acceleration
protected

Definition at line 135 of file vpRobotUniversalRobots.h.

Referenced by init().

◆ m_max_joint_speed

double vpRobotUniversalRobots::m_max_joint_speed
protected

Definition at line 134 of file vpRobotUniversalRobots.h.

Referenced by init(), and setPosition().

◆ m_max_linear_acceleration

double vpRobotUniversalRobots::m_max_linear_acceleration
protected

Definition at line 137 of file vpRobotUniversalRobots.h.

Referenced by init().

◆ m_max_linear_speed

double vpRobotUniversalRobots::m_max_linear_speed
protected

Definition at line 136 of file vpRobotUniversalRobots.h.

Referenced by init(), and setPosition().

◆ m_positioningVelocity

double vpRobotUniversalRobots::m_positioningVelocity
protected

Definition at line 133 of file vpRobotUniversalRobots.h.

Referenced by init(), setPosition(), and setPositioningVelocity().

◆ m_rtde_control

std::shared_ptr<ur_rtde::RTDEControlInterface> vpRobotUniversalRobots::m_rtde_control
protected

◆ m_rtde_receive

std::shared_ptr<ur_rtde::RTDEReceiveInterface> vpRobotUniversalRobots::m_rtde_receive
protected

◆ m_vel_control_frame

vpRobot::vpControlFrameType vpRobotUniversalRobots::m_vel_control_frame
protected

Definition at line 138 of file vpRobotUniversalRobots.h.

Referenced by init(), and setVelocity().

◆ maxRotationVelocity

◆ maxRotationVelocityDefault

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 101 of file vpRobot.h.

Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().

◆ maxTranslationVelocity

double vpRobot::maxTranslationVelocity
protectedinherited

◆ maxTranslationVelocityDefault

BEGIN_VISP_NAMESPACE const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 99 of file vpRobot.h.

Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().

◆ nDof

◆ qmax

double* vpRobot::qmax
protectedinherited

Definition at line 116 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

◆ qmin

double* vpRobot::qmin
protectedinherited

Definition at line 115 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

◆ verbose_