@@ -1379,20 +1379,42 @@ void URPositionHardwareInterface::check_passthrough_trajectory_controller()
13791379 // already received down to the hardware.
13801380 if (trajectory_started && point_index_sent <= trajectory_joint_positions_.size () &&
13811381 point_index_sent < point_index_received) {
1382+ bool error = false ;
13821383 /* Write the appropriate type of point depending on the combination of positions, velocities and accelerations. */
13831384 for (size_t i = point_index_sent; i < point_index_received; i++) {
1384- if (!has_velocities (trajectory_joint_velocities_) && !has_accelerations (trajectory_joint_accelerations_)) {
1385- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], urcl::vector6d_t { 0 , 0 , 0 , 0 , 0 , 0 },
1386- trajectory_times_[i]);
1387- } else if (has_velocities (trajectory_joint_velocities_) && !has_accelerations (trajectory_joint_accelerations_)) {
1388- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1389- trajectory_times_[i]);
1390- } else if (has_velocities (trajectory_joint_velocities_) && has_accelerations (trajectory_joint_accelerations_)) {
1391- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1392- trajectory_joint_accelerations_[i], trajectory_times_[i]);
1385+ if (is_valid_joint_information (trajectory_joint_positions_)) {
1386+ if (!is_valid_joint_information (trajectory_joint_velocities_) &&
1387+ !is_valid_joint_information (trajectory_joint_accelerations_)) {
1388+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], urcl::vector6d_t { 0 , 0 , 0 , 0 , 0 , 0 },
1389+ trajectory_times_[i]);
1390+ } else if (is_valid_joint_information (trajectory_joint_velocities_) &&
1391+ !is_valid_joint_information (trajectory_joint_accelerations_)) {
1392+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1393+ trajectory_times_[i]);
1394+ } else if (!is_valid_joint_information (trajectory_joint_velocities_) &&
1395+ is_valid_joint_information (trajectory_joint_accelerations_)) {
1396+ RCLCPP_ERROR (get_logger (), " Accelerations but no velocities given. If you want to specify accelerations with "
1397+ " a 0 velocity, please do that explicitly." );
1398+ error = true ;
1399+ break ;
1400+
1401+ } else if (is_valid_joint_information (trajectory_joint_velocities_) &&
1402+ is_valid_joint_information (trajectory_joint_accelerations_)) {
1403+ ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
1404+ trajectory_joint_accelerations_[i], trajectory_times_[i]);
1405+ }
1406+ } else {
1407+ RCLCPP_ERROR (get_logger (), " Trajectory points without position information are not supported." );
1408+ error = true ;
1409+ break ;
13931410 }
13941411 point_index_sent++;
13951412 }
1413+ if (error) {
1414+ passthrough_trajectory_abort_ = 1.0 ;
1415+ passthrough_trajectory_transfer_state_ = 5.0 ;
1416+ return ;
1417+ }
13961418 }
13971419}
13981420
@@ -1407,14 +1429,9 @@ void URPositionHardwareInterface::trajectory_done_callback(urcl::control::Trajec
14071429 return ;
14081430}
14091431
1410- bool URPositionHardwareInterface::has_velocities (std::vector<std::array<double , 6 >> velocities)
1411- {
1412- return (velocities.size () > 0 && !std::isnan (velocities[0 ][0 ]));
1413- }
1414-
1415- bool URPositionHardwareInterface::has_accelerations (std::vector<std::array<double , 6 >> accelerations)
1432+ bool URPositionHardwareInterface::is_valid_joint_information (std::vector<std::array<double , 6 >> data)
14161433{
1417- return (accelerations .size () > 0 && !std::isnan (accelerations [0 ][0 ]));
1434+ return (data .size () > 0 && !std::isnan (data [0 ][0 ]));
14181435}
14191436
14201437} // namespace ur_robot_driver
0 commit comments