1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

changed ROS interface to use set speed slider service

This commit is contained in:
Tristan Schnell
2019-08-01 13:39:04 +02:00
parent 402f3fb691
commit 4ddfe664d9
2 changed files with 22 additions and 10 deletions

View File

@@ -47,6 +47,7 @@
#include <ur_controllers/scaled_joint_command_interface.h>
#include "ur_rtde_driver/ur/ur_driver.h"
#include "ur_rtde_driver/SetSpeedSlider.h"
namespace ur_driver
{
@@ -111,7 +112,7 @@ protected:
void readBitsetData(const std::unique_ptr<rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
std::bitset<N>& data);
void speedScalingCallback(const std_msgs::Float64::ConstPtr& msg);
bool setSpeedSlider(ur_rtde_driver::SetSpeedSliderRequest& req, ur_rtde_driver::SetSpeedSliderResponse& res);
bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res);
std::unique_ptr<UrDriver> ur_driver_;
@@ -155,7 +156,7 @@ protected:
std::unique_ptr<realtime_tools::RealtimePublisher<ur_msgs::IOStates>> io_pub_;
std::unique_ptr<realtime_tools::RealtimePublisher<ur_msgs::ToolDataMsg>> tool_data_pub_;
ros::Subscriber speed_slider_sub_;
ros::ServiceServer set_speed_slider_srv_;
ros::ServiceServer set_io_srv_;
uint32_t runtime_state_;

View File

@@ -216,8 +216,7 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
}
tool_data_pub_.reset(new realtime_tools::RealtimePublisher<ur_msgs::ToolDataMsg>(robot_hw_nh, "tool_data", 1));
speed_slider_sub_ = robot_hw_nh.subscribe("set_speed_slider", 10, &HardwareInterface::speedScalingCallback, this);
set_speed_slider_srv_ = robot_hw_nh.advertiseService("set_speed_slider", &HardwareInterface::setSpeedSlider, this);
set_io_srv_ = robot_hw_nh.advertiseService("set_io", &HardwareInterface::setIO, this);
deactivate_srv_ = robot_hw_nh.advertiseService("hand_back_control", &HardwareInterface::stopControl, this);
@@ -538,9 +537,18 @@ bool HardwareInterface::stopControl(std_srvs::TriggerRequest& req, std_srvs::Tri
return true;
}
void HardwareInterface::speedScalingCallback(const std_msgs::Float64::ConstPtr& msg)
bool HardwareInterface::setSpeedSlider(ur_rtde_driver::SetSpeedSliderRequest& req,
ur_rtde_driver::SetSpeedSliderResponse& res)
{
ur_driver_->getRTDEWriter().sendSpeedSlider(msg->data);
if (req.data >= 0.01 && req.data <= 1.0)
{
res.success = ur_driver_->getRTDEWriter().sendSpeedSlider(req.data);
}
else
{
res.success = false;
}
return true;
}
bool HardwareInterface::setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res)
@@ -550,10 +558,13 @@ bool HardwareInterface::setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse
if (req.pin <= 7)
{
res.success = ur_driver_->getRTDEWriter().sendStandardDigitalOutput(req.pin, req.state);
} else if (req.pin <= 15)
}
else if (req.pin <= 15)
{
res.success = ur_driver_->getRTDEWriter().sendConfigurableDigitalOutput(req.pin - 8, req.state);
} else {
}
else
{
res.success = ur_driver_->getRTDEWriter().sendToolDigitalOutput(req.pin - 16, req.state);
}
}