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

Fixed naming of sendAnalogOutput function

This commit is contained in:
Felix Mauch
2019-09-19 16:29:36 +02:00
committed by Lea Steffen
parent 514740f524
commit d74708d2ee
3 changed files with 3 additions and 3 deletions

View File

@@ -52,7 +52,7 @@ public:
bool sendStandardDigitalOutput(uint8_t output_pin, bool value); bool sendStandardDigitalOutput(uint8_t output_pin, bool value);
bool sendConfigurableDigitalOutput(uint8_t output_pin, bool value); bool sendConfigurableDigitalOutput(uint8_t output_pin, bool value);
bool sendToolDigitalOutput(uint8_t output_pin, bool value); bool sendToolDigitalOutput(uint8_t output_pin, bool value);
bool sendStandardAnalogOuput(uint8_t output_pin, double value); bool sendStandardAnalogOutput(uint8_t output_pin, double value);
private: private:
uint8_t pinToMask(uint8_t pin); uint8_t pinToMask(uint8_t pin);

View File

@@ -571,7 +571,7 @@ bool HardwareInterface::setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse
} }
else if (req.fun == req.FUN_SET_ANALOG_OUT && ur_driver_ != nullptr) else if (req.fun == req.FUN_SET_ANALOG_OUT && ur_driver_ != nullptr)
{ {
res.success = ur_driver_->getRTDEWriter().sendStandardAnalogOuput(req.pin, req.state); res.success = ur_driver_->getRTDEWriter().sendStandardAnalogOutput(req.pin, req.state);
} }
else else
{ {

View File

@@ -164,7 +164,7 @@ bool RTDEWriter::sendToolDigitalOutput(uint8_t output_pin, bool value)
return success; return success;
} }
bool RTDEWriter::sendStandardAnalogOuput(uint8_t output_pin, double value) bool RTDEWriter::sendStandardAnalogOutput(uint8_t output_pin, double value)
{ {
std::unique_ptr<DataPackage> package; std::unique_ptr<DataPackage> package;
package.reset(new DataPackage(recipe_)); package.reset(new DataPackage(recipe_));