File tree Expand file tree Collapse file tree 1 file changed +0
-3
lines changed Expand file tree Collapse file tree 1 file changed +0
-3
lines changed Original file line number Diff line number Diff line change @@ -1400,9 +1400,6 @@ void URPositionHardwareInterface::check_passthrough_trajectory_controller()
14001400 } else if (has_velocities (trajectory_joint_velocities_) && !has_accelerations (trajectory_joint_accelerations_)) {
14011401 ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
14021402 trajectory_times_[i]);
1403- } else if (!has_velocities (trajectory_joint_velocities_) && has_accelerations (trajectory_joint_accelerations_)) {
1404- ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_accelerations_[i],
1405- trajectory_times_[i]);
14061403 } else if (has_velocities (trajectory_joint_velocities_) && has_accelerations (trajectory_joint_accelerations_)) {
14071404 ur_driver_->writeTrajectorySplinePoint (trajectory_joint_positions_[i], trajectory_joint_velocities_[i],
14081405 trajectory_joint_accelerations_[i], trajectory_times_[i]);
You can’t perform that action at this time.
0 commit comments