Public Member Functions | Private Member Functions | Private Attributes | List of all members
urcl::InstructionExecutor Class Reference

#include <instruction_executor.h>

Public Member Functions

bool cancelMotion ()
 Cancel the current motion. More...
 
bool executeMotion (const std::vector< std::shared_ptr< control::MotionPrimitive >> &motion_sequence)
 Execute a sequence of motion primitives. More...
 
 InstructionExecutor ()=delete
 
 InstructionExecutor (std::shared_ptr< urcl::UrDriver > driver)
 
bool isTrajectoryRunning () const
 Check if a trajectory is currently running. More...
 
bool moveC (const urcl::Pose &via, const urcl::Pose &target, const double acceleration=1.4, const double velocity=1.04, const double blend_radius=0.0, const int32_t mode=0)
 Move the robot to a pose target using movec. More...
 
bool moveJ (const urcl::vector6d_t &target, const double acceleration=1.4, const double velocity=1.04, const double time=0, const double blend_radius=0)
 Move the robot to a joint target. More...
 
bool moveL (const urcl::Pose &target, const double acceleration=1.4, const double velocity=1.04, const double time=0, const double blend_radius=0)
 Move the robot to a pose target using movel. More...
 
bool moveP (const urcl::Pose &target, const double acceleration=1.4, const double velocity=1.04, const double blend_radius=0.0)
 Move the robot to a pose target using movep. More...
 
 ~InstructionExecutor ()
 

Private Member Functions

void trajDisconnectCallback (const int filedescriptor)
 
void trajDoneCallback (const urcl::control::TrajectoryResult &result)
 

Private Attributes

std::atomic< bool > cancel_requested_ = false
 
std::shared_ptr< urcl::UrDriverdriver_
 
std::condition_variable trajectory_done_cv_
 
urcl::control::TrajectoryResult trajectory_result_
 
std::mutex trajectory_result_mutex_
 
std::atomic< bool > trajectory_running_ = false
 

Detailed Description

Definition at line 39 of file instruction_executor.h.

Constructor & Destructor Documentation

◆ InstructionExecutor() [1/2]

urcl::InstructionExecutor::InstructionExecutor ( )
delete

◆ InstructionExecutor() [2/2]

urcl::InstructionExecutor::InstructionExecutor ( std::shared_ptr< urcl::UrDriver driver)
inline

Definition at line 43 of file instruction_executor.h.

◆ ~InstructionExecutor()

urcl::InstructionExecutor::~InstructionExecutor ( )
inline

Definition at line 51 of file instruction_executor.h.

Member Function Documentation

◆ cancelMotion()

bool urcl::InstructionExecutor::cancelMotion ( )

Cancel the current motion.

If no motion is running, false will be returned. If a motion is running, it will be canceled and it will wait for a TRAJECTORY_CANCELED result with a timeout of one second.

If another result or no result is received, false will be returned.

Definition at line 122 of file src/ur/instruction_executor.cpp.

◆ executeMotion()

bool urcl::InstructionExecutor::executeMotion ( const std::vector< std::shared_ptr< control::MotionPrimitive >> &  motion_sequence)

Execute a sequence of motion primitives.

This function will execute a sequence of motion primitives. The robot will move according to the given motion primitives. The function will return once the robot has reached the final target.

Parameters
motion_sequenceThe sequence of motion primitives to execute

Definition at line 55 of file src/ur/instruction_executor.cpp.

◆ isTrajectoryRunning()

bool urcl::InstructionExecutor::isTrajectoryRunning ( ) const
inline

Check if a trajectory is currently running.

Definition at line 149 of file instruction_executor.h.

◆ moveC()

bool urcl::InstructionExecutor::moveC ( const urcl::Pose via,
const urcl::Pose target,
const double  acceleration = 1.4,
const double  velocity = 1.04,
const double  blend_radius = 0.0,
const int32_t  mode = 0 
)

Move the robot to a pose target using movec.

This function will move the robot to the given pose target in a circular motion going through via. The robot will move with the given acceleration and velocity. The function will return once the robot has reached the target.

Parameters
viaThe circle will be defined by the current pose (the end pose of the previous motion), the target and the via point.
targetThe pose target to move to.
accelerationTool acceleration [m/s^2]
velocityTool speed [m/s]
blend_radiusThe blend radius to use for the motion.
Returns
True if the robot has reached the target, false otherwise.

Definition at line 115 of file src/ur/instruction_executor.cpp.

◆ moveJ()

bool urcl::InstructionExecutor::moveJ ( const urcl::vector6d_t target,
const double  acceleration = 1.4,
const double  velocity = 1.04,
const double  time = 0,
const double  blend_radius = 0 
)

Move the robot to a joint target.

This function will move the robot to the given joint target. The robot will move with the given acceleration and velocity. The function will return once the robot has reached the target.

Parameters
targetThe joint target to move to.
accelerationJoint acceleration of leading axis [rad/s^2]
velocityJoint speed of leading axis [rad/s]
timeThe time to reach the target. If set to 0, the robot will move with the given acceleration and velocity.
blend_radiusThe blend radius to use for the motion.
Returns
True if the robot has reached the target, false otherwise.

Definition at line 96 of file src/ur/instruction_executor.cpp.

◆ moveL()

bool urcl::InstructionExecutor::moveL ( const urcl::Pose target,
const double  acceleration = 1.4,
const double  velocity = 1.04,
const double  time = 0,
const double  blend_radius = 0 
)

Move the robot to a pose target using movel.

This function will move the robot to the given pose target. The robot will move with the given acceleration and velocity or a motion time. The function will return once the robot has reached the target.

Parameters
targetThe pose target to move to.
accelerationTool acceleration [m/s^2]
velocityTool speed [m/s]
timeThe time to reach the target. If set to 0, the robot will move with the given acceleration and velocity.
blend_radiusThe blend radius to use for the motion.
Returns
True if the robot has reached the target, false otherwise.

Definition at line 102 of file src/ur/instruction_executor.cpp.

◆ moveP()

bool urcl::InstructionExecutor::moveP ( const urcl::Pose target,
const double  acceleration = 1.4,
const double  velocity = 1.04,
const double  blend_radius = 0.0 
)

Move the robot to a pose target using movep.

This function will move the robot to the given pose target. The robot will move with the given acceleration and velocity. The function will return once the robot has reached the target.

Parameters
targetThe pose target to move to.
accelerationTool acceleration [m/s^2]
velocityTool speed [m/s]
blend_radiusThe blend radius to use for the motion.
Returns
True if the robot has reached the target, false otherwise.

Definition at line 109 of file src/ur/instruction_executor.cpp.

◆ trajDisconnectCallback()

void urcl::InstructionExecutor::trajDisconnectCallback ( const int  filedescriptor)
private

Definition at line 44 of file src/ur/instruction_executor.cpp.

◆ trajDoneCallback()

void urcl::InstructionExecutor::trajDoneCallback ( const urcl::control::TrajectoryResult result)
private

Definition at line 36 of file src/ur/instruction_executor.cpp.

Member Data Documentation

◆ cancel_requested_

std::atomic<bool> urcl::InstructionExecutor::cancel_requested_ = false
private

Definition at line 159 of file instruction_executor.h.

◆ driver_

std::shared_ptr<urcl::UrDriver> urcl::InstructionExecutor::driver_
private

Definition at line 157 of file instruction_executor.h.

◆ trajectory_done_cv_

std::condition_variable urcl::InstructionExecutor::trajectory_done_cv_
private

Definition at line 161 of file instruction_executor.h.

◆ trajectory_result_

urcl::control::TrajectoryResult urcl::InstructionExecutor::trajectory_result_
private

Definition at line 162 of file instruction_executor.h.

◆ trajectory_result_mutex_

std::mutex urcl::InstructionExecutor::trajectory_result_mutex_
private

Definition at line 160 of file instruction_executor.h.

◆ trajectory_running_

std::atomic<bool> urcl::InstructionExecutor::trajectory_running_ = false
private

Definition at line 158 of file instruction_executor.h.


The documentation for this class was generated from the following files:


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Mon May 26 2025 02:35:58