1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-12 11:00:47 +02:00

Use SetSpeedSliderFraction.srv from ur_msgs

This commit is contained in:
Felix Mauch
2019-09-19 16:17:20 +02:00
committed by Tristan Schnell
parent 5123f68488
commit f3bc62a679
4 changed files with 6 additions and 9 deletions

View File

@@ -538,12 +538,12 @@ bool HardwareInterface::stopControl(std_srvs::TriggerRequest& req, std_srvs::Tri
return true;
}
bool HardwareInterface::setSpeedSlider(ur_rtde_msgs::SetSpeedSliderRequest& req,
ur_rtde_msgs::SetSpeedSliderResponse& res)
bool HardwareInterface::setSpeedSlider(ur_msgs::SetSpeedSliderFractionRequest& req,
ur_msgs::SetSpeedSliderFractionResponse& res)
{
if (req.data >= 0.01 && req.data <= 1.0 && ur_driver_ != nullptr)
if (req.speed_slider_fraction >= 0.01 && req.speed_slider_fraction <= 1.0 && ur_driver_ != nullptr)
{
res.success = ur_driver_->getRTDEWriter().sendSpeedSlider(req.data);
res.success = ur_driver_->getRTDEWriter().sendSpeedSlider(req.speed_slider_fraction);
}
else
{