Class InstructionExecutor

Class Documentation

class InstructionExecutor

Public Functions

InstructionExecutor() = delete
inline InstructionExecutor(std::shared_ptr<urcl::UrDriver> driver)
inline ~InstructionExecutor()
bool 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

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.

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.

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.

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.

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.

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.

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.

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.

bool optimoveJ(const urcl::vector6d_t &target, const double acceleration_fraction = 0.3, const double velocity_fraction = 0.3, const double blend_radius = 0)

Move the robot to a joint target using optimoveJ.

This function will move the robot to the given joint target using the optimoveJ motion primitive. The robot will move with the given acceleration and velocity fractions.

Parameters:
  • target – The joint target to move to.

  • acceleration_fraction – The fraction of the maximum acceleration to use for the motion (0.0 < fraction <= 1.0).

  • velocity_fraction – The fraction of the maximum velocity to use for the motion_sequence (0.0 < fraction <= 1.0).

  • blend_radius – The blend radius to use for the motion.

Returns:

True if the robot has reached the target, false otherwise.

bool optimoveL(const urcl::Pose &target, const double acceleration_fraction = 0.3, const double velocity_fraction = 0.3, const double blend_radius = 0)

Move the robot to a pose target using optimoveL.

This function will move the robot to the given pose target using the optimoveL motion primitive. The robot will move with the given acceleration and velocity fractions.

Parameters:
  • target – The pose target to move to.

  • acceleration_fraction – The fraction of the maximum acceleration to use for the motion (0.0 < fraction <= 1.0).

  • velocity_fraction – The fraction of the maximum velocity to use for the motion_sequence (0.0 < fraction <= 1.0).

  • blend_radius – The blend radius to use for the motion.

Returns:

True if the robot has reached the target, false otherwise.

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

inline bool isTrajectoryRunning() const

Check if a trajectory is currently running.

Protected Functions

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

Protected Attributes

uint32_t traj_done_callback_handler_id_
uint32_t disconnected_handler_id_
std::shared_ptr<urcl::UrDriver> driver_
std::atomic<bool> trajectory_running_ = false
std::atomic<bool> cancel_requested_ = false
std::mutex trajectory_result_mutex_
std::condition_variable trajectory_done_cv_
urcl::control::TrajectoryResult trajectory_result_