@@ -414,9 +414,6 @@ URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previou
414414 tool_comm_setup->setTxIdleChars (tx_idle_chars);
415415 }
416416
417- // Amount of allowed timed out reads before the reverse interface will be dropped
418- const int keep_alive_count = std::stoi (info_.hardware_parameters [" keep_alive_count" ]);
419-
420417 // Obtain the tf_prefix which is needed for the logging handler so that log messages from different arms are
421418 // distiguishable in the log
422419 const std::string tf_prefix = info_.hardware_parameters .at (" tf_prefix" );
@@ -429,7 +426,6 @@ URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previou
429426 std::bind (&URPositionHardwareInterface::handleRobotProgramState, this , std::placeholders::_1), headless_mode,
430427 std::move (tool_comm_setup), (uint32_t )reverse_port, (uint32_t )script_sender_port, servoj_gain,
431428 servoj_lookahead_time, non_blocking_read_, reverse_ip, trajectory_port, script_command_port);
432- ur_driver_->setKeepaliveCount (keep_alive_count);
433429 } catch (urcl::ToolCommNotAvailable& e) {
434430 RCLCPP_FATAL_STREAM (rclcpp::get_logger (" URPositionHardwareInterface" ), " See parameter use_tool_communication" );
435431
@@ -438,6 +434,9 @@ URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previou
438434 RCLCPP_FATAL_STREAM (rclcpp::get_logger (" URPositionHardwareInterface" ), e.what ());
439435 return hardware_interface::CallbackReturn::ERROR;
440436 }
437+ // Timeout before the reverse interface will be dropped by the robot
438+ receive_timeout_ = urcl::RobotReceiveTimeout::millisec (std::stoi (info_.hardware_parameters [" keep_alive_count" ]) * 20 );
439+
441440 RCLCPP_INFO (rclcpp::get_logger (" URPositionHardwareInterface" ), " Calibration checksum: '%s'." ,
442441 calibration_checksum.c_str ());
443442 // check calibration
@@ -627,10 +626,10 @@ hardware_interface::return_type URPositionHardwareInterface::write(const rclcpp:
627626 runtime_state_ == static_cast <uint32_t >(rtde::RUNTIME_STATE::PAUSING)) &&
628627 robot_program_running_ && (!non_blocking_read_ || packet_read_)) {
629628 if (position_controller_running_) {
630- ur_driver_->writeJointCommand (urcl_position_commands_, urcl::comm::ControlMode::MODE_SERVOJ);
629+ ur_driver_->writeJointCommand (urcl_position_commands_, urcl::comm::ControlMode::MODE_SERVOJ, receive_timeout_ );
631630
632631 } else if (velocity_controller_running_) {
633- ur_driver_->writeJointCommand (urcl_velocity_commands_, urcl::comm::ControlMode::MODE_SPEEDJ);
632+ ur_driver_->writeJointCommand (urcl_velocity_commands_, urcl::comm::ControlMode::MODE_SPEEDJ, receive_timeout_ );
634633
635634 } else {
636635 ur_driver_->writeKeepalive ();
0 commit comments