4545#include " ur_client_library/exceptions.h"
4646#include " ur_client_library/ur/tool_communication.h"
4747#include " ur_client_library/ur/version_information.h"
48+ #include " ur_client_library/ur/robot_receive_timeout.h"
4849
4950#include < rclcpp/logging.hpp>
5051#include " hardware_interface/types/hardware_interface_type_values.hpp"
@@ -93,9 +94,10 @@ URPositionHardwareInterface::on_init(const hardware_interface::HardwareInfo& sys
9394 freedrive_mode_abort_ = 0.0 ;
9495 passthrough_trajectory_transfer_state_ = 0.0 ;
9596 passthrough_trajectory_abort_ = 0.0 ;
96- trajectory_joint_positions_.clear ();
97- trajectory_joint_velocities_.clear ();
98- trajectory_joint_accelerations_.clear ();
97+ passthrough_trajectory_size_ = 0.0 ;
98+ trajectory_joint_positions_.reserve (32768 );
99+ trajectory_joint_velocities_.reserve (32768 );
100+ trajectory_joint_accelerations_.reserve (32768 );
99101
100102 for (const hardware_interface::ComponentInfo& joint : info_.joints ) {
101103 if (joint.command_interfaces .size () != 2 ) {
@@ -381,6 +383,9 @@ std::vector<hardware_interface::CommandInterface> URPositionHardwareInterface::e
381383 command_interfaces.emplace_back (
382384 hardware_interface::CommandInterface (tf_prefix + PASSTHROUGH_GPIO, " abort" , &passthrough_trajectory_abort_));
383385
386+ command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + PASSTHROUGH_GPIO, " trajectory_size" ,
387+ &passthrough_trajectory_size_));
388+
384389 for (size_t i = 0 ; i < 6 ; ++i) {
385390 command_interfaces.emplace_back (hardware_interface::CommandInterface (tf_prefix + PASSTHROUGH_GPIO,
386391 " setpoint_positions_" + std::to_string (i),
@@ -540,6 +545,9 @@ URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previou
540545 driver_config.handle_program_state =
541546 std::bind (&URPositionHardwareInterface::handleRobotProgramState, this , std::placeholders::_1);
542547 ur_driver_ = std::make_unique<urcl::UrDriver>(driver_config);
548+ if (ur_driver_->getControlFrequency () != info_.rw_rate ) {
549+ ur_driver_->resetRTDEClient (output_recipe_filename, input_recipe_filename, info_.rw_rate );
550+ }
543551 } catch (urcl::ToolCommNotAvailable& e) {
544552 RCLCPP_FATAL_STREAM (rclcpp::get_logger (" URPositionHardwareInterface" ), " See parameter use_tool_communication" );
545553
@@ -786,7 +794,9 @@ hardware_interface::return_type URPositionHardwareInterface::write(const rclcpp:
786794 ur_driver_->writeFreedriveControlMessage (urcl::control::FreedriveControlMessage::FREEDRIVE_NOOP);
787795
788796 } else if (passthrough_trajectory_controller_running_) {
789- ur_driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP);
797+ ur_driver_->writeTrajectoryControlMessage (
798+ urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP, 0 ,
799+ urcl::RobotReceiveTimeout::millisec (1000 * 5.0 / static_cast <double >(info_.rw_rate )));
790800 check_passthrough_trajectory_controller ();
791801 } else {
792802 ur_driver_->writeKeepalive ();
@@ -1322,59 +1332,102 @@ void URPositionHardwareInterface::stop_force_mode()
13221332void URPositionHardwareInterface::check_passthrough_trajectory_controller ()
13231333{
13241334 static double last_time = 0.0 ;
1335+ static size_t point_index_received = 0 ;
1336+ static size_t point_index_sent = 0 ;
1337+ static bool trajectory_started = false ;
13251338 // See passthrough_trajectory_controller.hpp for an explanation of the passthrough_trajectory_transfer_state_ values.
13261339
13271340 // We should abort and are not in state IDLE
13281341 if (passthrough_trajectory_abort_ == 1.0 && passthrough_trajectory_transfer_state_ != 0.0 ) {
13291342 ur_driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_CANCEL);
1343+ } else if (passthrough_trajectory_transfer_state_ == 6.0 ) {
1344+ if (passthrough_trajectory_size_ != trajectory_joint_positions_.size ()) {
1345+ RCLCPP_INFO (get_logger (), " Got a new trajectory with %lu points." ,
1346+ static_cast <size_t >(passthrough_trajectory_size_));
1347+ trajectory_joint_positions_.resize (passthrough_trajectory_size_);
1348+ trajectory_joint_velocities_.resize (passthrough_trajectory_size_);
1349+ trajectory_joint_accelerations_.resize (passthrough_trajectory_size_);
1350+ trajectory_times_.resize (passthrough_trajectory_size_);
1351+ point_index_received = 0 ;
1352+ point_index_sent = 0 ;
1353+ trajectory_started = false ;
1354+ last_time = 0.0 ;
1355+ passthrough_trajectory_transfer_state_ = 1.0 ;
1356+ }
13301357 } else if (passthrough_trajectory_transfer_state_ == 2.0 ) {
13311358 passthrough_trajectory_abort_ = 0.0 ;
1332- trajectory_joint_positions_. push_back ( passthrough_trajectory_positions_) ;
1359+ trajectory_joint_positions_[point_index_received] = passthrough_trajectory_positions_;
13331360
1334- trajectory_times_. push_back ( passthrough_trajectory_time_from_start_ - last_time) ;
1361+ trajectory_times_[point_index_received] = passthrough_trajectory_time_from_start_ - last_time;
13351362 last_time = passthrough_trajectory_time_from_start_;
13361363
1337- if (!std::isnan (passthrough_trajectory_velocities_[0 ])) {
1338- trajectory_joint_velocities_.push_back (passthrough_trajectory_velocities_);
1339- }
1340- if (!std::isnan (passthrough_trajectory_accelerations_[0 ])) {
1341- trajectory_joint_accelerations_.push_back (passthrough_trajectory_accelerations_);
1342- }
1364+ trajectory_joint_velocities_[point_index_received] = passthrough_trajectory_velocities_;
1365+ trajectory_joint_accelerations_[point_index_received] = passthrough_trajectory_accelerations_;
1366+
1367+ point_index_received++;
13431368 passthrough_trajectory_transfer_state_ = 1.0 ;
1344- /* When all points have been read, write them to the physical robot controller.*/
1369+
1370+ // Once we received enough points so we can move for at least 5 cycles, we start executing
1371+ if ((passthrough_trajectory_time_from_start_ > 5.0 / static_cast <double >(info_.rw_rate ) ||
1372+ point_index_received == passthrough_trajectory_size_ - 1 ) &&
1373+ !trajectory_started) {
1374+ ur_driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
1375+ trajectory_joint_positions_.size ());
1376+ trajectory_started = true ;
1377+ }
13451378 } else if (passthrough_trajectory_transfer_state_ == 3.0 ) {
1346- /* Tell robot controller how many points are in the trajectory. */
1347- ur_driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
1348- trajectory_joint_positions_.size ());
1379+ passthrough_trajectory_abort_ = 0.0 ;
1380+ passthrough_trajectory_transfer_state_ = 4.0 ;
1381+ } else if (passthrough_trajectory_transfer_state_ == 4.0 ) {
1382+ if (point_index_sent == trajectory_joint_positions_.size ()) {
1383+ trajectory_joint_positions_.clear ();
1384+ trajectory_joint_accelerations_.clear ();
1385+ trajectory_joint_velocities_.clear ();
1386+ trajectory_times_.clear ();
1387+ last_time = 0.0 ;
1388+ }
1389+ }
1390+
1391+ // We basically get a setpoint from the controller in each cycle. We send all the points that we
1392+ // already received down to the hardware.
1393+ if (trajectory_started && point_index_sent <= trajectory_joint_positions_.size () &&
1394+ point_index_sent < point_index_received) {
1395+ bool error = false ;
13491396 /* Write the appropriate type of point depending on the combination of positions, velocities and accelerations. */
1350- if (!has_velocities (trajectory_joint_velocities_) && !has_accelerations (trajectory_joint_accelerations_)) {
1351- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1352- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], urcl::vector6d_t { 0 , 0 , 0 , 0 , 0 , 0 },
1353- trajectory_times_[i]);
1354- }
1355- } else if (has_velocities (trajectory_joint_velocities_) && !has_accelerations (trajectory_joint_accelerations_)) {
1356- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1357- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1358- trajectory_times_[i]);
1359- }
1360- } else if (!has_velocities (trajectory_joint_velocities_) && has_accelerations (trajectory_joint_accelerations_)) {
1361- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1362- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_accelerations_[i],
1363- trajectory_times_[i]);
1364- }
1365- } else if (has_velocities (trajectory_joint_velocities_) && has_accelerations (trajectory_joint_accelerations_)) {
1366- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1367- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1368- trajectory_joint_accelerations_[i], trajectory_times_[i]);
1397+ for (size_t i = point_index_sent; i < point_index_received; i++) {
1398+ if (is_valid_joint_information (trajectory_joint_positions_)) {
1399+ if (!is_valid_joint_information (trajectory_joint_velocities_) &&
1400+ !is_valid_joint_information (trajectory_joint_accelerations_)) {
1401+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], urcl::vector6d_t { 0 , 0 , 0 , 0 , 0 , 0 },
1402+ trajectory_times_[i]);
1403+ } else if (is_valid_joint_information (trajectory_joint_velocities_) &&
1404+ !is_valid_joint_information (trajectory_joint_accelerations_)) {
1405+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1406+ trajectory_times_[i]);
1407+ } else if (!is_valid_joint_information (trajectory_joint_velocities_) &&
1408+ is_valid_joint_information (trajectory_joint_accelerations_)) {
1409+ RCLCPP_ERROR (get_logger (), " Accelerations but no velocities given. If you want to specify accelerations with "
1410+ " a 0 velocity, please do that explicitly." );
1411+ error = true ;
1412+ break ;
1413+
1414+ } else if (is_valid_joint_information (trajectory_joint_velocities_) &&
1415+ is_valid_joint_information (trajectory_joint_accelerations_)) {
1416+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1417+ trajectory_joint_accelerations_[i], trajectory_times_[i]);
1418+ }
1419+ } else {
1420+ RCLCPP_ERROR (get_logger (), " Trajectory points without position information are not supported." );
1421+ error = true ;
1422+ break ;
13691423 }
1424+ point_index_sent++;
1425+ }
1426+ if (error) {
1427+ passthrough_trajectory_abort_ = 1.0 ;
1428+ passthrough_trajectory_transfer_state_ = 5.0 ;
1429+ return ;
13701430 }
1371- trajectory_joint_positions_.clear ();
1372- trajectory_joint_accelerations_.clear ();
1373- trajectory_joint_velocities_.clear ();
1374- trajectory_times_.clear ();
1375- last_time = 0.0 ;
1376- passthrough_trajectory_abort_ = 0.0 ;
1377- passthrough_trajectory_transfer_state_ = 4.0 ;
13781431 }
13791432}
13801433
@@ -1389,14 +1442,9 @@ void URPositionHardwareInterface::trajectory_done_callback(urcl::control::Trajec
13891442 return ;
13901443}
13911444
1392- bool URPositionHardwareInterface::has_velocities (std::vector<std::array<double , 6 >> velocities)
1393- {
1394- return (velocities.size () > 0 );
1395- }
1396-
1397- bool URPositionHardwareInterface::has_accelerations (std::vector<std::array<double , 6 >> accelerations)
1445+ bool URPositionHardwareInterface::is_valid_joint_information (std::vector<std::array<double , 6 >> data)
13981446{
1399- return (accelerations .size () > 0 );
1447+ return (data .size () > 0 && ! std::isnan (data[ 0 ][ 0 ]) );
14001448}
14011449
14021450} // namespace ur_robot_driver
0 commit comments