Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add a set_analog_output service #714

Merged
merged 2 commits into from
Sep 30, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions ur_robot_driver/include/ur_robot_driver/hardware_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
#include <ur_client_library/control/trajectory_point_interface.h>
#include <ur_msgs/IOStates.h>
#include <ur_msgs/ToolDataMsg.h>
#include <ur_msgs/SetAnalogOutput.h>
#include <ur_msgs/SetIO.h>
#include <ur_msgs/SetSpeedSliderFraction.h>
#include <ur_msgs/SetPayload.h>
Expand Down Expand Up @@ -211,6 +212,7 @@ class HardwareInterface : public hardware_interface::RobotHW

bool setSpeedSlider(ur_msgs::SetSpeedSliderFractionRequest& req, ur_msgs::SetSpeedSliderFractionResponse& res);
bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res);
bool setAnalogOutput(ur_msgs::SetAnalogOutputRequest& req, ur_msgs::SetAnalogOutputResponse& res);
bool resendRobotProgram(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
bool zeroFTSensor(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
void commandCallback(const std_msgs::StringConstPtr& msg);
Expand Down Expand Up @@ -319,6 +321,7 @@ class HardwareInterface : public hardware_interface::RobotHW

ros::ServiceServer set_speed_slider_srv_;
ros::ServiceServer set_io_srv_;
ros::ServiceServer set_analog_output_srv_;
ros::ServiceServer resend_robot_program_srv_;
ros::Subscriber command_sub_;

Expand Down
13 changes: 12 additions & 1 deletion ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -435,8 +435,9 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
// doing. Using this with other controllers might lead to unexpected behaviors.
set_speed_slider_srv_ = robot_hw_nh.advertiseService("set_speed_slider", &HardwareInterface::setSpeedSlider, this);

// Service to set any of the robot's IOs
// Services to set any of the robot's IOs
set_io_srv_ = robot_hw_nh.advertiseService("set_io", &HardwareInterface::setIO, this);
set_analog_output_srv_ = robot_hw_nh.advertiseService("set_analog_output", &HardwareInterface::setAnalogOutput, this);

if (headless_mode)
{
Expand Down Expand Up @@ -1135,6 +1136,16 @@ bool HardwareInterface::setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse
return true;
}

bool HardwareInterface::setAnalogOutput(ur_msgs::SetAnalogOutputRequest& req, ur_msgs::SetAnalogOutputResponse& res)
{
if (ur_driver_)
{
res.success = ur_driver_->getRTDEWriter().sendStandardAnalogOutput(
req.data.pin, req.data.state, static_cast<urcl::AnalogOutputType>(req.data.domain));
}
return true;
}

bool HardwareInterface::resendRobotProgram(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
{
res.success = ur_driver_->sendRobotProgram();
Expand Down