22 #include <ur_msgs/SetIO.h> 23 #include <ur_msgs/SetIORequest.h> 24 #include <ur_msgs/SetIOResponse.h> 25 #include <ur_msgs/SetPayload.h> 26 #include <ur_msgs/SetPayloadRequest.h> 27 #include <ur_msgs/SetPayloadResponse.h> 39 bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& resp)
41 LOG_INFO(
"setIO called with [%d, %d]", req.fun, req.pin);
43 bool flag = req.state > 0.0 ?
true :
false;
46 case ur_msgs::SetIO::Request::FUN_SET_DIGITAL_OUT:
49 case ur_msgs::SetIO::Request::FUN_SET_ANALOG_OUT:
52 case ur_msgs::SetIO::Request::FUN_SET_TOOL_VOLTAGE:
55 case ur_msgs::SetIO::Request::FUN_SET_FLAG:
56 res = commander_.
setFlag(req.pin, flag);
59 LOG_WARN(
"Invalid setIO function called (%d)", req.fun);
62 return (resp.success = res);
65 bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& resp)
69 return (resp.success = commander_.
setPayload(req.payload));
74 : commander_(commander)
virtual bool setDigitalOut(uint8_t pin, bool value)=0
bool setPayload(ur_msgs::SetPayloadRequest &req, ur_msgs::SetPayloadResponse &resp)
bool setIO(ur_msgs::SetIORequest &req, ur_msgs::SetIOResponse &resp)
IOService(URCommander &commander)
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
bool setToolVoltage(uint8_t voltage)
bool setPayload(double value)
ros::ServiceServer io_service_
bool setFlag(uint8_t pin, bool value)
#define LOG_INFO(format,...)
ros::ServiceServer payload_service_
virtual bool setAnalogOut(uint8_t pin, double value)=0
#define LOG_WARN(format,...)