2929// -- END LICENSE BLOCK ------------------------------------------------
3030
3131#include " ur_client_library/ur/instruction_executor.h"
32+ #include < mutex>
3233#include " ur_client_library/control/trajectory_point_interface.h"
3334void urcl::InstructionExecutor::trajDoneCallback (const urcl::control::TrajectoryResult& result)
3435{
36+ URCL_LOG_DEBUG (" Trajectory result received: %s" , control::trajectoryResultToString (result).c_str ());
3537 std::unique_lock<std::mutex> lock (trajectory_result_mutex_);
38+ trajectory_done_cv_.notify_all ();
3639 trajectory_result_ = result;
3740 trajectory_running_ = false ;
3841}
3942void urcl::InstructionExecutor::trajDisconnectCallback (const int filedescriptor)
4043{
4144 URCL_LOG_INFO (" Trajectory disconnect" );
4245 std::unique_lock<std::mutex> lock (trajectory_result_mutex_);
46+ trajectory_done_cv_.notify_all ();
4347 if (trajectory_running_)
4448 {
4549 trajectory_result_ = urcl::control::TrajectoryResult::TRAJECTORY_RESULT_FAILURE;
@@ -86,17 +90,20 @@ bool urcl::InstructionExecutor::executeMotion(
8690 }
8791 }
8892 trajectory_running_ = true ;
93+ cancel_requested_ = false ;
8994
90- while (trajectory_running_)
95+ while (trajectory_running_ && !cancel_requested_ )
9196 {
92- std::this_thread::sleep_for (std::chrono::milliseconds (100 ));
9397 driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP);
98+ std::this_thread::sleep_for (std::chrono::milliseconds (100 ));
9499 }
100+ if (!cancel_requested_)
95101 {
96102 std::unique_lock<std::mutex> lock (trajectory_result_mutex_);
97103 URCL_LOG_INFO (" Trajectory done with result %s" , control::trajectoryResultToString (trajectory_result_).c_str ());
98104 return trajectory_result_ == urcl::control::TrajectoryResult::TRAJECTORY_RESULT_SUCCESS;
99105 }
106+ return false ;
100107}
101108bool urcl::InstructionExecutor::moveJ (const urcl::vector6d_t & target, const double acceleration, const double velocity,
102109 const double time, const double blend_radius)
@@ -110,3 +117,19 @@ bool urcl::InstructionExecutor::moveL(const urcl::Pose& target, const double acc
110117 return executeMotion ({ std::make_shared<control::MoveLPrimitive>(
111118 target, blend_radius, std::chrono::milliseconds (static_cast <int >(time * 1000 )), acceleration, velocity) });
112119}
120+
121+ bool urcl::InstructionExecutor::cancelMotion ()
122+ {
123+ cancel_requested_ = true ;
124+ if (trajectory_running_)
125+ {
126+ URCL_LOG_INFO (" Cancel motion" );
127+ driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_CANCEL);
128+ std::unique_lock<std::mutex> lock (trajectory_result_mutex_);
129+ if (trajectory_done_cv_.wait_for (lock, std::chrono::milliseconds (1000 )) == std::cv_status::no_timeout)
130+ {
131+ return trajectory_result_ == urcl::control::TrajectoryResult::TRAJECTORY_RESULT_CANCELED;
132+ }
133+ }
134+ return false ;
135+ }
0 commit comments