mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Use SetSpeedSliderFraction.srv from ur_msgs
This commit is contained in:
committed by
Tristan Schnell
parent
5123f68488
commit
f3bc62a679
@@ -25,7 +25,6 @@ find_package(catkin REQUIRED
|
|||||||
trajectory_msgs
|
trajectory_msgs
|
||||||
ur_controllers
|
ur_controllers
|
||||||
ur_msgs
|
ur_msgs
|
||||||
ur_rtde_msgs
|
|
||||||
)
|
)
|
||||||
find_package(Boost REQUIRED)
|
find_package(Boost REQUIRED)
|
||||||
|
|
||||||
@@ -50,7 +49,6 @@ catkin_package(
|
|||||||
ur_controllers
|
ur_controllers
|
||||||
ur_msgs
|
ur_msgs
|
||||||
std_srvs
|
std_srvs
|
||||||
ur_rtde_msgs
|
|
||||||
DEPENDS
|
DEPENDS
|
||||||
Boost
|
Boost
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -43,12 +43,12 @@
|
|||||||
#include <ur_msgs/IOStates.h>
|
#include <ur_msgs/IOStates.h>
|
||||||
#include <ur_msgs/ToolDataMsg.h>
|
#include <ur_msgs/ToolDataMsg.h>
|
||||||
#include <ur_msgs/SetIO.h>
|
#include <ur_msgs/SetIO.h>
|
||||||
|
#include "ur_msgs/SetSpeedSliderFraction.h"
|
||||||
|
|
||||||
#include <ur_controllers/speed_scaling_interface.h>
|
#include <ur_controllers/speed_scaling_interface.h>
|
||||||
#include <ur_controllers/scaled_joint_command_interface.h>
|
#include <ur_controllers/scaled_joint_command_interface.h>
|
||||||
|
|
||||||
#include "ur_rtde_driver/ur/ur_driver.h"
|
#include "ur_rtde_driver/ur/ur_driver.h"
|
||||||
#include "ur_rtde_msgs/SetSpeedSlider.h"
|
|
||||||
|
|
||||||
namespace ur_driver
|
namespace ur_driver
|
||||||
{
|
{
|
||||||
@@ -113,7 +113,7 @@ protected:
|
|||||||
void readBitsetData(const std::unique_ptr<rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
|
void readBitsetData(const std::unique_ptr<rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
|
||||||
std::bitset<N>& data);
|
std::bitset<N>& data);
|
||||||
|
|
||||||
bool setSpeedSlider(ur_rtde_msgs::SetSpeedSliderRequest& req, ur_rtde_msgs::SetSpeedSliderResponse& res);
|
bool setSpeedSlider(ur_msgs::SetSpeedSliderFractionRequest& req, ur_msgs::SetSpeedSliderFractionResponse& res);
|
||||||
bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res);
|
bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res);
|
||||||
void commandCallback(const std_msgs::StringConstPtr& msg);
|
void commandCallback(const std_msgs::StringConstPtr& msg);
|
||||||
|
|
||||||
|
|||||||
@@ -35,7 +35,6 @@
|
|||||||
<depend>ur_controllers</depend>
|
<depend>ur_controllers</depend>
|
||||||
<depend>ur_msgs</depend>
|
<depend>ur_msgs</depend>
|
||||||
<depend>std_srvs</depend>
|
<depend>std_srvs</depend>
|
||||||
<depend>ur_rtde_msgs</depend>
|
|
||||||
|
|
||||||
<exec_depend>force_torque_sensor_controller</exec_depend>
|
<exec_depend>force_torque_sensor_controller</exec_depend>
|
||||||
<exec_depend>joint_state_controller</exec_depend>
|
<exec_depend>joint_state_controller</exec_depend>
|
||||||
|
|||||||
@@ -538,12 +538,12 @@ bool HardwareInterface::stopControl(std_srvs::TriggerRequest& req, std_srvs::Tri
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool HardwareInterface::setSpeedSlider(ur_rtde_msgs::SetSpeedSliderRequest& req,
|
bool HardwareInterface::setSpeedSlider(ur_msgs::SetSpeedSliderFractionRequest& req,
|
||||||
ur_rtde_msgs::SetSpeedSliderResponse& res)
|
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
|
else
|
||||||
{
|
{
|
||||||
|
|||||||
Reference in New Issue
Block a user