mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 19:10:47 +02:00
Removed hardcoded velocity limit in vel_based ros_control
This commit is contained in:
@@ -163,10 +163,6 @@ void UrHardwareInterface::write() {
|
|||||||
< prev_joint_velocity_command_[i] - max_vel_change_) {
|
< prev_joint_velocity_command_[i] - max_vel_change_) {
|
||||||
cmd[i] = prev_joint_velocity_command_[i] - max_vel_change_;
|
cmd[i] = prev_joint_velocity_command_[i] - max_vel_change_;
|
||||||
}
|
}
|
||||||
if (cmd[i] > M_PI/2.)
|
|
||||||
cmd[i] = M_PI/2.;
|
|
||||||
else if (cmd[i] < -M_PI/2.)
|
|
||||||
cmd[i] = -M_PI/2.;
|
|
||||||
prev_joint_velocity_command_[i] = cmd[i];
|
prev_joint_velocity_command_[i] = cmd[i];
|
||||||
}
|
}
|
||||||
robot_->setSpeed(cmd[0], cmd[1], cmd[2], cmd[3], cmd[4], cmd[5], max_vel_change_*125);
|
robot_->setSpeed(cmd[0], cmd[1], cmd[2], cmd[3], cmd[4], cmd[5], max_vel_change_*125);
|
||||||
|
|||||||
Reference in New Issue
Block a user