diff --git a/src/ur_realtime_communication.cpp b/src/ur_realtime_communication.cpp index f841455..90f0cfe 100644 --- a/src/ur_realtime_communication.cpp +++ b/src/ur_realtime_communication.cpp @@ -98,9 +98,16 @@ void UrRealtimeCommunication::addCommandToQueue(std::string inp) { void UrRealtimeCommunication::setSpeed(double q0, double q1, double q2, double q3, double q4, double q5, double acc) { char cmd[1024]; - sprintf(cmd, - "speedj([%1.5f, %1.5f, %1.5f, %1.5f, %1.5f, %1.5f], %f, 0.02)\n", - q0, q1, q2, q3, q4, q5, acc); + if( robot_state_->getVersion() >= 3.1 ) { + sprintf(cmd, + "speedj([%1.5f, %1.5f, %1.5f, %1.5f, %1.5f, %1.5f], %f)\n", + q0, q1, q2, q3, q4, q5, acc); + } + else { + sprintf(cmd, + "speedj([%1.5f, %1.5f, %1.5f, %1.5f, %1.5f, %1.5f], %f, 0.02)\n", + q0, q1, q2, q3, q4, q5, acc); + } addCommandToQueue((std::string) (cmd)); if (q0 != 0. or q1 != 0. or q2 != 0. or q3 != 0. or q4 != 0. or q5 != 0.) { //If a joint speed is set, make sure we stop it again after some time if the user doesn't