Skip to content

Commit f887c09

Browse files
committed
Check passthrough trajectory controller from write function
This should be thread-safe in contrast to calling it from the AsyncIO thread.
1 parent ca7aff9 commit f887c09

File tree

1 file changed

+1
-3
lines changed

1 file changed

+1
-3
lines changed

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -572,9 +572,6 @@ void URPositionHardwareInterface::asyncThread()
572572
if (initialized_) {
573573
// RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Initialized in async thread");
574574
checkAsyncIO();
575-
if (passthrough_trajectory_controller_running_) {
576-
check_passthrough_trajectory_controller();
577-
}
578575
}
579576
std::this_thread::sleep_for(std::chrono::nanoseconds(20000000));
580577
}
@@ -692,6 +689,7 @@ hardware_interface::return_type URPositionHardwareInterface::write(const rclcpp:
692689

693690
} else if (passthrough_trajectory_controller_running_) {
694691
ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP);
692+
check_passthrough_trajectory_controller();
695693
} else {
696694
ur_driver_->writeKeepalive();
697695
}

0 commit comments

Comments
 (0)