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),
@@ -1335,59 +1340,104 @@ void URPositionHardwareInterface::stop_force_mode()
13351340void URPositionHardwareInterface::check_passthrough_trajectory_controller ()
13361341{
13371342 static double last_time = 0.0 ;
1343+ static size_t point_index_received = 0 ;
1344+ static size_t point_index_sent = 0 ;
1345+ static bool trajectory_started = false ;
13381346 // See passthrough_trajectory_controller.hpp for an explanation of the passthrough_trajectory_transfer_state_ values.
13391347
13401348 // We should abort and are not in state IDLE
13411349 if (passthrough_trajectory_abort_ == 1.0 && passthrough_trajectory_transfer_state_ != 0.0 ) {
13421350 ur_driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_CANCEL);
1351+ } else if (passthrough_trajectory_transfer_state_ == 6.0 ) {
1352+ if (passthrough_trajectory_size_ != trajectory_joint_positions_.size ()) {
1353+ RCLCPP_INFO (rclcpp::get_logger (" URPositionHardwareInterface" ), " Got a new trajectory with %lu points." ,
1354+ static_cast <size_t >(passthrough_trajectory_size_));
1355+ trajectory_joint_positions_.resize (passthrough_trajectory_size_);
1356+ trajectory_joint_velocities_.resize (passthrough_trajectory_size_);
1357+ trajectory_joint_accelerations_.resize (passthrough_trajectory_size_);
1358+ trajectory_times_.resize (passthrough_trajectory_size_);
1359+ point_index_received = 0 ;
1360+ point_index_sent = 0 ;
1361+ trajectory_started = false ;
1362+ last_time = 0.0 ;
1363+ passthrough_trajectory_transfer_state_ = 1.0 ;
1364+ }
13431365 } else if (passthrough_trajectory_transfer_state_ == 2.0 ) {
13441366 passthrough_trajectory_abort_ = 0.0 ;
1345- trajectory_joint_positions_. push_back ( passthrough_trajectory_positions_) ;
1367+ trajectory_joint_positions_[point_index_received] = passthrough_trajectory_positions_;
13461368
1347- trajectory_times_. push_back ( passthrough_trajectory_time_from_start_ - last_time) ;
1369+ trajectory_times_[point_index_received] = passthrough_trajectory_time_from_start_ - last_time;
13481370 last_time = passthrough_trajectory_time_from_start_;
13491371
1350- if (!std::isnan (passthrough_trajectory_velocities_[0 ])) {
1351- trajectory_joint_velocities_.push_back (passthrough_trajectory_velocities_);
1352- }
1353- if (!std::isnan (passthrough_trajectory_accelerations_[0 ])) {
1354- trajectory_joint_accelerations_.push_back (passthrough_trajectory_accelerations_);
1355- }
1372+ trajectory_joint_velocities_[point_index_received] = passthrough_trajectory_velocities_;
1373+ trajectory_joint_accelerations_[point_index_received] = passthrough_trajectory_accelerations_;
1374+
1375+ point_index_received++;
13561376 passthrough_trajectory_transfer_state_ = 1.0 ;
1357- /* When all points have been read, write them to the physical robot controller.*/
1377+
1378+ // Once we received enough points so we can move for at least 5 cycles, we start executing
1379+ if ((passthrough_trajectory_time_from_start_ > 5.0 / static_cast <double >(ur_driver_->getControlFrequency ()) ||
1380+ point_index_received == passthrough_trajectory_size_ - 1 ) &&
1381+ !trajectory_started) {
1382+ ur_driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
1383+ trajectory_joint_positions_.size ());
1384+ trajectory_started = true ;
1385+ }
13581386 } else if (passthrough_trajectory_transfer_state_ == 3.0 ) {
1359- /* Tell robot controller how many points are in the trajectory. */
1360- ur_driver_->writeTrajectoryControlMessage (urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
1361- trajectory_joint_positions_.size ());
1387+ passthrough_trajectory_abort_ = 0.0 ;
1388+ passthrough_trajectory_transfer_state_ = 4.0 ;
1389+ } else if (passthrough_trajectory_transfer_state_ == 4.0 ) {
1390+ if (point_index_sent == trajectory_joint_positions_.size ()) {
1391+ trajectory_joint_positions_.clear ();
1392+ trajectory_joint_accelerations_.clear ();
1393+ trajectory_joint_velocities_.clear ();
1394+ trajectory_times_.clear ();
1395+ last_time = 0.0 ;
1396+ }
1397+ }
1398+
1399+ // We basically get a setpoint from the controller in each cycle. We send all the points that we
1400+ // already received down to the hardware.
1401+ if (trajectory_started && point_index_sent <= trajectory_joint_positions_.size () &&
1402+ point_index_sent < point_index_received) {
1403+ bool error = false ;
13621404 /* Write the appropriate type of point depending on the combination of positions, velocities and accelerations. */
1363- if (!has_velocities (trajectory_joint_velocities_) && !has_accelerations (trajectory_joint_accelerations_)) {
1364- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1365- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], urcl::vector6d_t { 0 , 0 , 0 , 0 , 0 , 0 },
1366- trajectory_times_[i]);
1367- }
1368- } else if (has_velocities (trajectory_joint_velocities_) && !has_accelerations (trajectory_joint_accelerations_)) {
1369- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1370- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1371- trajectory_times_[i]);
1372- }
1373- } else if (!has_velocities (trajectory_joint_velocities_) && has_accelerations (trajectory_joint_accelerations_)) {
1374- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1375- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_accelerations_[i],
1376- trajectory_times_[i]);
1377- }
1378- } else if (has_velocities (trajectory_joint_velocities_) && has_accelerations (trajectory_joint_accelerations_)) {
1379- for (size_t i = 0 ; i < trajectory_joint_positions_.size (); i++) {
1380- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1381- trajectory_joint_accelerations_[i], trajectory_times_[i]);
1405+ for (size_t i = point_index_sent; i < point_index_received; i++) {
1406+ if (is_valid_joint_information (trajectory_joint_positions_)) {
1407+ if (!is_valid_joint_information (trajectory_joint_velocities_) &&
1408+ !is_valid_joint_information (trajectory_joint_accelerations_)) {
1409+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], urcl::vector6d_t { 0 , 0 , 0 , 0 , 0 , 0 },
1410+ trajectory_times_[i]);
1411+ } else if (is_valid_joint_information (trajectory_joint_velocities_) &&
1412+ !is_valid_joint_information (trajectory_joint_accelerations_)) {
1413+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1414+ trajectory_times_[i]);
1415+ } else if (!is_valid_joint_information (trajectory_joint_velocities_) &&
1416+ is_valid_joint_information (trajectory_joint_accelerations_)) {
1417+ RCLCPP_ERROR (rclcpp::get_logger (" URPositionHardwareInterface" ), " Accelerations but no velocities given. If "
1418+ " you want to specify accelerations with "
1419+ " a 0 velocity, please do that explicitly." );
1420+ error = true ;
1421+ break ;
1422+
1423+ } else if (is_valid_joint_information (trajectory_joint_velocities_) &&
1424+ is_valid_joint_information (trajectory_joint_accelerations_)) {
1425+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1426+ trajectory_joint_accelerations_[i], trajectory_times_[i]);
1427+ }
1428+ } else {
1429+ RCLCPP_ERROR (rclcpp::get_logger (" URPositionHardwareInterface" ), " Trajectory points without position "
1430+ " information are not supported." );
1431+ error = true ;
1432+ break ;
13821433 }
1434+ point_index_sent++;
1435+ }
1436+ if (error) {
1437+ passthrough_trajectory_abort_ = 1.0 ;
1438+ passthrough_trajectory_transfer_state_ = 5.0 ;
1439+ return ;
13831440 }
1384- trajectory_joint_positions_.clear ();
1385- trajectory_joint_accelerations_.clear ();
1386- trajectory_joint_velocities_.clear ();
1387- trajectory_times_.clear ();
1388- last_time = 0.0 ;
1389- passthrough_trajectory_abort_ = 0.0 ;
1390- passthrough_trajectory_transfer_state_ = 4.0 ;
13911441 }
13921442}
13931443
@@ -1402,14 +1452,9 @@ void URPositionHardwareInterface::trajectory_done_callback(urcl::control::Trajec
14021452 return ;
14031453}
14041454
1405- bool URPositionHardwareInterface::has_velocities (std::vector<std::array<double , 6 >> velocities)
1406- {
1407- return (velocities.size () > 0 );
1408- }
1409-
1410- bool URPositionHardwareInterface::has_accelerations (std::vector<std::array<double , 6 >> accelerations)
1455+ bool URPositionHardwareInterface::is_valid_joint_information (std::vector<std::array<double , 6 >> data)
14111456{
1412- return (accelerations .size () > 0 );
1457+ return (data .size () > 0 && ! std::isnan (data[ 0 ][ 0 ]) );
14131458}
14141459
14151460} // namespace ur_robot_driver
0 commit comments