diff --git a/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_writer.h b/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_writer.h index 02506e8..280e978 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_writer.h +++ b/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_writer.h @@ -52,7 +52,7 @@ public: bool sendStandardDigitalOutput(uint8_t output_pin, bool value); bool sendConfigurableDigitalOutput(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: uint8_t pinToMask(uint8_t pin); diff --git a/ur_rtde_driver/src/ros/hardware_interface.cpp b/ur_rtde_driver/src/ros/hardware_interface.cpp index e14e0ca..add8bb0 100644 --- a/ur_rtde_driver/src/ros/hardware_interface.cpp +++ b/ur_rtde_driver/src/ros/hardware_interface.cpp @@ -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) { - res.success = ur_driver_->getRTDEWriter().sendStandardAnalogOuput(req.pin, req.state); + res.success = ur_driver_->getRTDEWriter().sendStandardAnalogOutput(req.pin, req.state); } else { diff --git a/ur_rtde_driver/src/rtde/rtde_writer.cpp b/ur_rtde_driver/src/rtde/rtde_writer.cpp index a8e5fb8..4f7fefe 100644 --- a/ur_rtde_driver/src/rtde/rtde_writer.cpp +++ b/ur_rtde_driver/src/rtde/rtde_writer.cpp @@ -164,7 +164,7 @@ bool RTDEWriter::sendToolDigitalOutput(uint8_t output_pin, bool value) return success; } -bool RTDEWriter::sendStandardAnalogOuput(uint8_t output_pin, double value) +bool RTDEWriter::sendStandardAnalogOutput(uint8_t output_pin, double value) { std::unique_ptr package; package.reset(new DataPackage(recipe_));