Main Content

getEndEffectorVelocity

Get current end-effector velocities from the robot

Since R2022a

Description

eevelocity=getEndEffectorVelocity(ur) waits for the next published joint state from the Universal Robots cobot connected through ROS interface, and returns current end-effector velocities. If no message is received in 5 seconds, the function displays an error.

eevelocity=getEndEffectorVelocity(ur,timeout) allows you to specify a timeout for obtaining the current end-effector velocities from the Universal Robots cobot connected through ROS interface. If no message is received within the specified time, the function displays an error.

example

Examples

collapse all

Connect to a physical or simulated cobot, using either urROSNode or urROS2Node object (based on the option for connectivity – ROS or ROS 2, which you selected in the Hardware Setup screen).

  • Connect to a physical or simulated cobot at IP address 192.168.2.112 on the ROS network.

    ur = urROSNode('192.168.2.112');
  • Connect to a physical or simulated cobot on the ROS 2 network.

    ur = urROS2Node;

Get the current end-effector velocities of the cobot, representing the current position velocity and orientation velocity of the end-effector.

eevelocity = getEndEffectorVelocity(ur);
eeVelocity = 1×6    
10-12 x

   -0.0617    0.1266   -0.0363   -0.1783    0.0645    0.0046

Specify a timeout of 10 seconds while obtaining current end-effector velocities of the cobot.

jointangles = getCartesianPose(ur,10);

Input Arguments

collapse all

Connection to physical or simulated cobot from Universal Robots, specified as a urROSNode object or a urROS2Node object.

Timeout value by which the end-effector velocities must be obtained from the simulated cobot, specified in seconds.

Data Types: double

Output Arguments

collapse all

Current end effector velocities, returned as a 1-by-6 vector consisting of the three orientation velocity and three position velocity values (represented as [thetaz(dot) thetay(dot) thetax(dot) Vx Vy Vz]) in rad/s and m/s respectively.

Data Types: double

Extended Capabilities

C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.

Version History

Introduced in R2022a

See Also

getJointConfiguration | getJointVelocity | |