#include <instruction_executor.h>
|
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 () |
|
Definition at line 39 of file instruction_executor.h.
◆ InstructionExecutor() [1/2]
urcl::InstructionExecutor::InstructionExecutor |
( |
| ) |
|
|
delete |
◆ InstructionExecutor() [2/2]
urcl::InstructionExecutor::InstructionExecutor |
( |
std::shared_ptr< urcl::UrDriver > |
driver | ) |
|
|
inline |
◆ ~InstructionExecutor()
urcl::InstructionExecutor::~InstructionExecutor |
( |
| ) |
|
|
inline |
◆ 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_sequence | The sequence of motion primitives to execute |
Definition at line 55 of file src/ur/instruction_executor.cpp.
◆ isTrajectoryRunning()
bool urcl::InstructionExecutor::isTrajectoryRunning |
( |
| ) |
const |
|
inline |
◆ 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
-
via | The circle will be defined by the current pose (the end pose of the previous motion), the target and the via point. |
target | The pose target to move to. |
acceleration | Tool acceleration [m/s^2] |
velocity | Tool speed [m/s] |
blend_radius | The 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
-
target | The joint target to move to. |
acceleration | Joint acceleration of leading axis [rad/s^2] |
velocity | Joint speed of leading axis [rad/s] |
time | The time to reach the target. If set to 0, the robot will move with the given acceleration and velocity. |
blend_radius | The 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
-
target | The pose target to move to. |
acceleration | Tool acceleration [m/s^2] |
velocity | Tool speed [m/s] |
time | The time to reach the target. If set to 0, the robot will move with the given acceleration and velocity. |
blend_radius | The 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
-
target | The pose target to move to. |
acceleration | Tool acceleration [m/s^2] |
velocity | Tool speed [m/s] |
blend_radius | The 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 |
◆ trajDoneCallback()
◆ cancel_requested_
std::atomic<bool> urcl::InstructionExecutor::cancel_requested_ = false |
|
private |
◆ driver_
◆ trajectory_done_cv_
std::condition_variable urcl::InstructionExecutor::trajectory_done_cv_ |
|
private |
◆ trajectory_result_
◆ trajectory_result_mutex_
std::mutex urcl::InstructionExecutor::trajectory_result_mutex_ |
|
private |
◆ trajectory_running_
std::atomic<bool> urcl::InstructionExecutor::trajectory_running_ = false |
|
private |
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