From 704de8abe5d8a5091ceeff1344f80092a57c8064 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bartek=20=C5=81ukawski?= Date: Fri, 19 Jan 2018 17:58:25 +0100 Subject: [PATCH] Add new parameter methods to ICartesianControl, prepare stub impl (#121) --- .../AmorCartesianControl.hpp | 8 +++ .../ICartesianControlImpl.cpp | 28 +++++++++++ .../BasicCartesianControl.hpp | 8 +++ .../ICartesianControlImpl.cpp | 28 +++++++++++ .../CartesianControlClient.hpp | 8 +++ .../ICartesianControlImpl.cpp | 28 +++++++++++ libraries/YarpPlugins/ICartesianControl.h | 49 +++++++++++++++++++ 7 files changed, 157 insertions(+) diff --git a/libraries/YarpPlugins/AmorCartesianControl/AmorCartesianControl.hpp b/libraries/YarpPlugins/AmorCartesianControl/AmorCartesianControl.hpp index 0bc4a282d..f69d8c570 100644 --- a/libraries/YarpPlugins/AmorCartesianControl/AmorCartesianControl.hpp +++ b/libraries/YarpPlugins/AmorCartesianControl/AmorCartesianControl.hpp @@ -79,6 +79,14 @@ class AmorCartesianControl : public yarp::dev::DeviceDriver, public ICartesianCo virtual void pose(const std::vector &x, double interval); + virtual bool setParameter(int vocab, const std::string & value); + + virtual bool getParameter(int vocab, std::string & value); + + virtual bool setParameter(int vocab, double value); + + virtual bool setParameter(int vocab, double * value); + // -------- DeviceDriver declarations. Implementation in DeviceDriverImpl.cpp -------- /** diff --git a/libraries/YarpPlugins/AmorCartesianControl/ICartesianControlImpl.cpp b/libraries/YarpPlugins/AmorCartesianControl/ICartesianControlImpl.cpp index 73e6952c9..a0a959423 100644 --- a/libraries/YarpPlugins/AmorCartesianControl/ICartesianControlImpl.cpp +++ b/libraries/YarpPlugins/AmorCartesianControl/ICartesianControlImpl.cpp @@ -575,3 +575,31 @@ void roboticslab::AmorCartesianControl::pose(const std::vector &x, doubl } // ----------------------------------------------------------------------------- + +bool roboticslab::AmorCartesianControl::setParameter(int vocab, const std::string & value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::AmorCartesianControl::getParameter(int vocab, std::string & value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::AmorCartesianControl::setParameter(int vocab, double value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::AmorCartesianControl::setParameter(int vocab, double * value) +{ + return true; +} + +// ----------------------------------------------------------------------------- diff --git a/libraries/YarpPlugins/BasicCartesianControl/BasicCartesianControl.hpp b/libraries/YarpPlugins/BasicCartesianControl/BasicCartesianControl.hpp index 9d44c00c1..d236aa951 100644 --- a/libraries/YarpPlugins/BasicCartesianControl/BasicCartesianControl.hpp +++ b/libraries/YarpPlugins/BasicCartesianControl/BasicCartesianControl.hpp @@ -150,6 +150,14 @@ class BasicCartesianControl : public yarp::dev::DeviceDriver, public ICartesianC virtual void pose(const std::vector &x, double interval); + virtual bool setParameter(int vocab, const std::string & value); + + virtual bool getParameter(int vocab, std::string & value); + + virtual bool setParameter(int vocab, double value); + + virtual bool setParameter(int vocab, double * value); + // -------- RateThread declarations. Implementation in RateThreadImpl.cpp -------- /** Loop function. This is the thread itself. */ diff --git a/libraries/YarpPlugins/BasicCartesianControl/ICartesianControlImpl.cpp b/libraries/YarpPlugins/BasicCartesianControl/ICartesianControlImpl.cpp index 915fc804b..970114a15 100644 --- a/libraries/YarpPlugins/BasicCartesianControl/ICartesianControlImpl.cpp +++ b/libraries/YarpPlugins/BasicCartesianControl/ICartesianControlImpl.cpp @@ -586,3 +586,31 @@ void roboticslab::BasicCartesianControl::pose(const std::vector &x, doub } // ----------------------------------------------------------------------------- + +bool roboticslab::BasicCartesianControl::setParameter(int vocab, const std::string & value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::BasicCartesianControl::getParameter(int vocab, std::string & value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::BasicCartesianControl::setParameter(int vocab, double value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::BasicCartesianControl::setParameter(int vocab, double * value) +{ + return true; +} + +// ----------------------------------------------------------------------------- diff --git a/libraries/YarpPlugins/CartesianControlClient/CartesianControlClient.hpp b/libraries/YarpPlugins/CartesianControlClient/CartesianControlClient.hpp index 06d9c9348..2bdb8d2b5 100644 --- a/libraries/YarpPlugins/CartesianControlClient/CartesianControlClient.hpp +++ b/libraries/YarpPlugins/CartesianControlClient/CartesianControlClient.hpp @@ -101,6 +101,14 @@ class CartesianControlClient : public yarp::dev::DeviceDriver, public ICartesian virtual void pose(const std::vector &x, double interval); + virtual bool setParameter(int vocab, const std::string & value); + + virtual bool getParameter(int vocab, std::string & value); + + virtual bool setParameter(int vocab, double value); + + virtual bool setParameter(int vocab, double * value); + // -------- DeviceDriver declarations. Implementation in IDeviceImpl.cpp -------- /** diff --git a/libraries/YarpPlugins/CartesianControlClient/ICartesianControlImpl.cpp b/libraries/YarpPlugins/CartesianControlClient/ICartesianControlImpl.cpp index 44ef63bd2..fb9ffdfba 100644 --- a/libraries/YarpPlugins/CartesianControlClient/ICartesianControlImpl.cpp +++ b/libraries/YarpPlugins/CartesianControlClient/ICartesianControlImpl.cpp @@ -261,3 +261,31 @@ void roboticslab::CartesianControlClient::pose(const std::vector &x, dou } // ----------------------------------------------------------------------------- + +bool roboticslab::CartesianControlClient::setParameter(int vocab, const std::string & value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::CartesianControlClient::getParameter(int vocab, std::string & value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::CartesianControlClient::setParameter(int vocab, double value) +{ + return true; +} + +// ----------------------------------------------------------------------------- + +bool roboticslab::CartesianControlClient::setParameter(int vocab, double * value) +{ + return true; +} + +// ----------------------------------------------------------------------------- diff --git a/libraries/YarpPlugins/ICartesianControl.h b/libraries/YarpPlugins/ICartesianControl.h index aa16f4e3d..b0017ce8b 100644 --- a/libraries/YarpPlugins/ICartesianControl.h +++ b/libraries/YarpPlugins/ICartesianControl.h @@ -3,6 +3,7 @@ #ifndef __I_CARTESIAN_CONTROL__ #define __I_CARTESIAN_CONTROL__ +#include #include #include @@ -342,6 +343,54 @@ class ICartesianControl */ virtual void pose(const std::vector &x, double interval) = 0; + /** + * @brief Set a configuration parameter. + * + * Ask the controller to store or update a parameter of type std::string. + * + * @param vocab YARP-encoded vocab (parameter key). + * @param value Parameter value encoded as a string. + * + * @return true on success, false otherwise + */ + virtual bool setParameter(int vocab, const std::string & value) = 0; + + /** + * @brief Retrieve a configuration parameter. + * + * Ask the controller to retrieve a parameter of type std::string. + * + * @param vocab YARP-encoded vocab (parameter key). + * @param value Parameter value encoded as a string. + * + * @return true on success, false otherwise + */ + virtual bool getParameter(int vocab, std::string & value) = 0; + + /** + * @brief Set a configuration parameter. + * + * Ask the controller to store or update a parameter of type double. + * + * @param vocab YARP-encoded vocab (parameter key). + * @param value Parameter value encoded as a double. + * + * @return true on success, false otherwise + */ + virtual bool setParameter(int vocab, double value) = 0; + + /** + * @brief Retrieve a configuration parameter. + * + * Ask the controller to retrieve a parameter of type double. + * + * @param vocab YARP-encoded vocab (parameter key). + * @param value Parameter value encoded as a double. + * + * @return true on success, false otherwise + */ + virtual bool setParameter(int vocab, double * value) = 0; + /** @} */ };