From 7b732fdcb989a882a3aea65e891b8b9f917b337f Mon Sep 17 00:00:00 2001 From: dorianleveque Date: Mon, 23 Nov 2020 11:01:03 +0100 Subject: [PATCH 01/17] lead-through methods added --- include/abb_librws/rws_client.h | 19 +++++++++++++++++++ include/abb_librws/rws_common.h | 30 ++++++++++++++++++++++++++++++ include/abb_librws/rws_interface.h | 27 +++++++++++++++++++++++++++ src/rws_client.cpp | 23 +++++++++++++++++++++++ src/rws_common.cpp | 6 ++++++ src/rws_interface.cpp | 17 +++++++++++++++++ 6 files changed, 122 insertions(+) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index a1b3743e..580b56c4 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -592,6 +592,25 @@ class RWSClient : public POCOClient */ RWSResult setSpeedRatio(unsigned int ratio); + /** + * \brief A method for retrieving the lead-through state of the controller. + * + * \param mechunit for the mechanical unit's name. + * + * \return RWSResult containing the result. + */ + RWSResult getLeadThrough(const std::string& mechunit); + + /** + * \brief A method for setting the lead-through state of the controller. + * + * \param mechunit for the mechanical unit's name. + * \param value for the lead-through new value. + * + * \return RWSResult containing the result. + */ + RWSResult setLeadThrough(const std::string& mechunit, const std::string& value); + /** * \brief A method for retrieving a file from the robot controller. * diff --git a/include/abb_librws/rws_common.h b/include/abb_librws/rws_common.h index 52b823e4..6e7d77d0 100644 --- a/include/abb_librws/rws_common.h +++ b/include/abb_librws/rws_common.h @@ -161,6 +161,11 @@ struct SystemConstants */ struct ABB_LIBRWS_EXPORT ContollerStates { + /** + * \brief Robot controller active state. + */ + static const std::string ACTIVE; + /** * \brief Robot controller motor on. */ @@ -492,6 +497,11 @@ struct SystemConstants */ static const XMLAttribute CLASS_STATE; + /** + * \brief Class & status. + */ + static const XMLAttribute CLASS_STATUS; + /** * \brief Class & sys-option-li. */ @@ -578,6 +588,11 @@ struct SystemConstants */ static const std::string HOME_DIRECTORY; + /** + * \brief Inactive type. + */ + static const std::string INACTIVE; + /** * \brief IO signal. */ @@ -653,6 +668,11 @@ struct SystemConstants */ static const std::string STATE; + /** + * \brief Status. + */ + static const std::string STATUS; + /** * \brief Controller topic in the system configurations (abbreviated as sys). */ @@ -709,6 +729,11 @@ struct SystemConstants */ static const std::string ACTION_RESETPP; + /** + * \brief Get lead-through resource query. + */ + static const std::string RESOURCE_LEAD_THROUGH; + /** * \brief Set action query. */ @@ -719,6 +744,11 @@ struct SystemConstants */ static const std::string ACTION_SETCTRLSTATE; + /** + * \brief Set lead-through action query. + */ + static const std::string ACTION_SET_LEAD_THROUGH; + /** * \brief Set locale. */ diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 26806709..031c8275 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -762,6 +762,33 @@ class RWSInterface */ bool setSpeedRatio(unsigned int ratio); + /** + * \brief A method for turning on the lead-through modes. + * + * \param mechunit for the mechanical unit's name. + * + * \return bool indicating if the communication was successful or not. + */ + bool setLeadThroughOn(const std::string& mechunit); + + /** + * \brief A method for turning off the lead-through modes. + * + * \param mechunit for the mechanical unit's name. + * + * \return bool indicating if the communication was successful or not. + */ + bool setLeadThroughOff(const std::string& mechunit); + + /** + * \brief A method for checking if the lead-through are on. + * + * \param mechunit for the mechanical unit's name. + * + * \return TriBool indicating if the lead-through are on or not or unknown. + */ + TriBool isLeadThroughOn(const std::string& mechunit); + /** * \brief A method for retrieving a file from the robot controller. * diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 256caf70..417c9e0e 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -474,6 +474,29 @@ RWSClient::RWSResult RWSClient::setSpeedRatio(unsigned int ratio) return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } +RWSClient::RWSResult RWSClient::getLeadThrough(const std::string& mechunit) +{ + std::string uri = generateMechanicalUnitPath(mechunit) + "?" + Queries::RESOURCE_LEAD_THROUGH; + + EvaluationConditions evaluation_conditions; + evaluation_conditions.parse_message_into_xml = true; + evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); + + return evaluatePOCOResult(httpGet(uri), evaluation_conditions); +} + +RWSClient::RWSResult RWSClient::setLeadThrough(const std::string& mechunit, const std::string& value) +{ + std::string uri = generateMechanicalUnitPath(mechunit) + "?" + Queries::ACTION_SET_LEAD_THROUGH; + std::string content = Identifiers::STATUS + "=" + value; + + EvaluationConditions evaluation_conditions; + evaluation_conditions.parse_message_into_xml = false; + evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); + + return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); +} + RWSClient::RWSResult RWSClient::getFile(const FileResource& resource, std::string* p_file_content) { RWSResult rws_result; diff --git a/src/rws_common.cpp b/src/rws_common.cpp index 56a37c8f..5913b32a 100644 --- a/src/rws_common.cpp +++ b/src/rws_common.cpp @@ -213,6 +213,7 @@ typedef SystemConstants::RWS::Resources Resources; typedef SystemConstants::RWS::Services Services; typedef SystemConstants::RWS::XMLAttributes XMLAttributes; +const std::string SystemConstants::ContollerStates::ACTIVE = "Active"; const std::string SystemConstants::ContollerStates::CONTROLLER_MOTOR_ON = "motoron"; const std::string SystemConstants::ContollerStates::CONTROLLER_MOTOR_OFF = "motoroff"; const std::string SystemConstants::ContollerStates::PANEL_OPERATION_MODE_AUTO = "AUTO"; @@ -267,6 +268,7 @@ const std::string Identifiers::CTRLEXECSTATE = "ctrlexecstate"; const std::string Identifiers::CTRLSTATE = "ctrlstate"; const std::string Identifiers::DATTYP = "dattyp"; const std::string Identifiers::EXCSTATE = "excstate"; +const std::string Identifiers::INACTIVE = "inactive"; const std::string Identifiers::IOS_SIGNAL = "ios-signal"; const std::string Identifiers::HOME_DIRECTORY = "$home"; const std::string Identifiers::LVALUE = "lvalue"; @@ -283,6 +285,7 @@ const std::string Identifiers::ROBOT = "robot"; const std::string Identifiers::RW_VERSION_NAME = "rwversionname"; const std::string Identifiers::SINGLE = "single"; const std::string Identifiers::STATE = "state"; +const std::string Identifiers::STATUS = "status"; const std::string Identifiers::SYS = "sys"; const std::string Identifiers::SYS_OPTION_LI = "sys-option-li"; const std::string Identifiers::SYS_SYSTEM_LI = "sys-system-li"; @@ -296,9 +299,11 @@ const std::string Queries::ACTION_REQUEST = "action=request" const std::string Queries::ACTION_RESETPP = "action=resetpp"; const std::string Queries::ACTION_SET = "action=set"; const std::string Queries::ACTION_SETCTRLSTATE = "action=setctrlstate"; +const std::string Queries::ACTION_SET_LEAD_THROUGH = "action=set-lead-through"; const std::string Queries::ACTION_SET_LOCALE = "action=set-locale"; const std::string Queries::ACTION_START = "action=start"; const std::string Queries::ACTION_STOP = "action=stop"; +const std::string Queries::RESOURCE_LEAD_THROUGH = "resource=lead-through"; const std::string Queries::TASK = "task="; const std::string Services::CTRL = "/ctrl"; const std::string Services::FILESERVICE = "/fileservice"; @@ -339,6 +344,7 @@ const XMLAttribute XMLAttributes::CLASS_RAP_MODULE_INFO_LI(Identifiers::CLASS, I const XMLAttribute XMLAttributes::CLASS_RAP_TASK_LI(Identifiers::CLASS , Identifiers::RAP_TASK_LI); const XMLAttribute XMLAttributes::CLASS_RW_VERSION_NAME(Identifiers::CLASS , Identifiers::RW_VERSION_NAME); const XMLAttribute XMLAttributes::CLASS_STATE(Identifiers::CLASS , Identifiers::STATE); +const XMLAttribute XMLAttributes::CLASS_STATUS(Identifiers::CLASS , Identifiers::STATUS); const XMLAttribute XMLAttributes::CLASS_SYS_OPTION_LI(Identifiers::CLASS , Identifiers::SYS_OPTION_LI); const XMLAttribute XMLAttributes::CLASS_SYS_SYSTEM_LI(Identifiers::CLASS , Identifiers::SYS_SYSTEM_LI); const XMLAttribute XMLAttributes::CLASS_TYPE(Identifiers::CLASS , Identifiers::TYPE); diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index b964aee9..d2ef3841 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -978,6 +978,23 @@ bool RWSInterface::getRAPIDSymbolData(const std::string& task, return rws_client_.getRAPIDSymbolData(RWSClient::RAPIDResource(task, symbol), p_data).success; } +bool RWSInterface::setLeadThroughOn(const std::string& mechunit) +{ + return rws_client_.setLeadThrough(mechunit, Identifiers::ACTIVE).success; +} + +bool RWSInterface::setLeadThroughOff(const std::string& mechunit) +{ + return rws_client_.setLeadThrough(mechunit, Identifiers::INACTIVE).success; +} + +TriBool RWSInterface::isLeadThroughOn(const std::string& mechunit) +{ + return compareSingleContent(rws_client_.getLeadThrough(mechunit), + XMLAttributes::CLASS_STATUS, + ContollerStates::ACTIVE); +} + bool RWSInterface::getFile(const RWSClient::FileResource& resource, std::string* p_file_content) { return rws_client_.getFile(resource, p_file_content).success; From 20380cb9dff7c4f9501d9dbb3bbe2e3cd2c81b4c Mon Sep 17 00:00:00 2001 From: dorianleveque Date: Mon, 23 Nov 2020 11:35:36 +0100 Subject: [PATCH 02/17] load module methods added --- include/abb_librws/rws_client.h | 33 +++++++++++++------- include/abb_librws/rws_common.h | 50 ++++++++++++------------------ include/abb_librws/rws_interface.h | 26 ++++++---------- src/rws_client.cpp | 30 +++++++++++------- src/rws_common.cpp | 10 +++--- src/rws_interface.cpp | 15 +++------ 6 files changed, 78 insertions(+), 86 deletions(-) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index 580b56c4..122ac3d4 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -593,23 +593,25 @@ class RWSClient : public POCOClient RWSResult setSpeedRatio(unsigned int ratio); /** - * \brief A method for retrieving the lead-through state of the controller. + * \brief A method for loading a module to the robot controller. + * + * \param task specifying the RAPID task. + * \param resource specifying the file's directory and name. + * \param replace indicating if the actual module into the controller must be replaced by the new one or not. * - * \param mechunit for the mechanical unit's name. - * * \return RWSResult containing the result. - */ - RWSResult getLeadThrough(const std::string& mechunit); - + */ + RWSResult loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace = false); + /** - * \brief A method for setting the lead-through state of the controller. + * \brief A method for unloading a module to the robot controller. * - * \param mechunit for the mechanical unit's name. - * \param value for the lead-through new value. + * \param task specifying the RAPID task. + * \param resource specifying the file's directory and name. * * \return RWSResult containing the result. - */ - RWSResult setLeadThrough(const std::string& mechunit, const std::string& value); + */ + RWSResult unloadModuleFromTask(const std::string& task, const FileResource& resource); /** * \brief A method for retrieving a file from the robot controller. @@ -844,6 +846,15 @@ class RWSClient : public POCOClient */ std::string generateFilePath(const FileResource& resource); + /** + * \brief Method for generating a task resource URI path. + * + * \param task for the task name. + * + * \return std::string containing the path. + */ + std::string generateRAPIDTasksPath(const std::string& task); + /** * \brief Static constant for the log's size. */ diff --git a/include/abb_librws/rws_common.h b/include/abb_librws/rws_common.h index 6e7d77d0..fb93f137 100644 --- a/include/abb_librws/rws_common.h +++ b/include/abb_librws/rws_common.h @@ -161,11 +161,6 @@ struct SystemConstants */ struct ABB_LIBRWS_EXPORT ContollerStates { - /** - * \brief Robot controller active state. - */ - static const std::string ACTIVE; - /** * \brief Robot controller motor on. */ @@ -497,11 +492,6 @@ struct SystemConstants */ static const XMLAttribute CLASS_STATE; - /** - * \brief Class & status. - */ - static const XMLAttribute CLASS_STATUS; - /** * \brief Class & sys-option-li. */ @@ -588,11 +578,6 @@ struct SystemConstants */ static const std::string HOME_DIRECTORY; - /** - * \brief Inactive type. - */ - static const std::string INACTIVE; - /** * \brief IO signal. */ @@ -613,6 +598,16 @@ struct SystemConstants */ static const std::string MOC; + /** + * \brief Module name. + */ + static const std::string MODULE; + + /** + * \brief Module path. + */ + static const std::string MODULEPATH; + /** * \brief Motion task. */ @@ -668,11 +663,6 @@ struct SystemConstants */ static const std::string STATE; - /** - * \brief Status. - */ - static const std::string STATUS; - /** * \brief Controller topic in the system configurations (abbreviated as sys). */ @@ -714,6 +704,11 @@ struct SystemConstants */ struct ABB_LIBRWS_EXPORT Queries { + /** + * \brief Load module action query. + */ + static const std::string ACTION_LOAD_MODULE; + /** * \brief Release action query. */ @@ -729,11 +724,6 @@ struct SystemConstants */ static const std::string ACTION_RESETPP; - /** - * \brief Get lead-through resource query. - */ - static const std::string RESOURCE_LEAD_THROUGH; - /** * \brief Set action query. */ @@ -744,11 +734,6 @@ struct SystemConstants */ static const std::string ACTION_SETCTRLSTATE; - /** - * \brief Set lead-through action query. - */ - static const std::string ACTION_SET_LEAD_THROUGH; - /** * \brief Set locale. */ @@ -764,6 +749,11 @@ struct SystemConstants */ static const std::string ACTION_STOP; + /** + * \brief Unload module action query. + */ + static const std::string ACTION_UNLOAD_MODULE; + /** * \brief Task query. */ diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 031c8275..74150769 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -763,31 +763,25 @@ class RWSInterface bool setSpeedRatio(unsigned int ratio); /** - * \brief A method for turning on the lead-through modes. + * \brief A method for loading a module to the robot controller. * - * \param mechunit for the mechanical unit's name. + * \param task specifying the RAPID task. + * \param resource specifying the file's directory and name. + * \param replace indicating if the actual module into the controller must be replaced by the new one or not. * * \return bool indicating if the communication was successful or not. - */ - bool setLeadThroughOn(const std::string& mechunit); + */ + bool loadModuleIntoTask(const std::string& task, const RWSClient::FileResource& resource, const bool replace = false); /** - * \brief A method for turning off the lead-through modes. + * \brief A method for unloading a module to the robot controller. * - * \param mechunit for the mechanical unit's name. + * \param task specifying the RAPID task. + * \param resource specifying the file's directory and name. * * \return bool indicating if the communication was successful or not. - */ - bool setLeadThroughOff(const std::string& mechunit); - - /** - * \brief A method for checking if the lead-through are on. - * - * \param mechunit for the mechanical unit's name. - * - * \return TriBool indicating if the lead-through are on or not or unknown. */ - TriBool isLeadThroughOn(const std::string& mechunit); + bool unloadModuleFromTask(const std::string& task, const RWSClient::FileResource& resource); /** * \brief A method for retrieving a file from the robot controller. diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 417c9e0e..2f43358a 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -474,26 +474,27 @@ RWSClient::RWSResult RWSClient::setSpeedRatio(unsigned int ratio) return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getLeadThrough(const std::string& mechunit) +RWSClient::RWSResult RWSClient::loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace) { - std::string uri = generateMechanicalUnitPath(mechunit) + "?" + Queries::RESOURCE_LEAD_THROUGH; - + std::string uri = generateRAPIDTasksPath(task) + "?" + Queries::ACTION_LOAD_MODULE; + std::string content = Identifiers::MODULEPATH + "=" + generateFilePath(resource) + "&replace=" + ((replace) ? "true" : "false"); + EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = true; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); - - return evaluatePOCOResult(httpGet(uri), evaluation_conditions); + evaluation_conditions.parse_message_into_xml = false; + evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); + + return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::setLeadThrough(const std::string& mechunit, const std::string& value) +RWSClient::RWSResult RWSClient::unloadModuleFromTask(const std::string& task, const FileResource& resource) { - std::string uri = generateMechanicalUnitPath(mechunit) + "?" + Queries::ACTION_SET_LEAD_THROUGH; - std::string content = Identifiers::STATUS + "=" + value; - + std::string uri = generateRAPIDTasksPath(task) + "?" + Queries::ACTION_UNLOAD_MODULE; + std::string content = Identifiers::MODULE + "=" + resource.filename; + EvaluationConditions evaluation_conditions; evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - + return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } @@ -821,5 +822,10 @@ std::string RWSClient::generateFilePath(const FileResource& resource) return Services::FILESERVICE + "/" + resource.directory + "/" + resource.filename; } +std::string RWSClient::generateRAPIDTasksPath(const std::string& task) +{ + return Resources::RW_RAPID_TASKS + "/" + task; +} + } // end namespace rws } // end namespace abb diff --git a/src/rws_common.cpp b/src/rws_common.cpp index 5913b32a..3c1f0bfe 100644 --- a/src/rws_common.cpp +++ b/src/rws_common.cpp @@ -213,7 +213,6 @@ typedef SystemConstants::RWS::Resources Resources; typedef SystemConstants::RWS::Services Services; typedef SystemConstants::RWS::XMLAttributes XMLAttributes; -const std::string SystemConstants::ContollerStates::ACTIVE = "Active"; const std::string SystemConstants::ContollerStates::CONTROLLER_MOTOR_ON = "motoron"; const std::string SystemConstants::ContollerStates::CONTROLLER_MOTOR_OFF = "motoroff"; const std::string SystemConstants::ContollerStates::PANEL_OPERATION_MODE_AUTO = "AUTO"; @@ -268,13 +267,14 @@ const std::string Identifiers::CTRLEXECSTATE = "ctrlexecstate"; const std::string Identifiers::CTRLSTATE = "ctrlstate"; const std::string Identifiers::DATTYP = "dattyp"; const std::string Identifiers::EXCSTATE = "excstate"; -const std::string Identifiers::INACTIVE = "inactive"; const std::string Identifiers::IOS_SIGNAL = "ios-signal"; const std::string Identifiers::HOME_DIRECTORY = "$home"; const std::string Identifiers::LVALUE = "lvalue"; const std::string Identifiers::MECHANICAL_UNIT = "mechanical_unit"; const std::string Identifiers::MECHANICAL_UNIT_GROUP = "mechanical_unit_group"; const std::string Identifiers::MOC = "moc"; +const std::string Identifiers::MODULE = "module"; +const std::string Identifiers::MODULEPATH = "modulepath"; const std::string Identifiers::MOTIONTASK = "motiontask"; const std::string Identifiers::NAME = "name"; const std::string Identifiers::OPMODE = "opmode"; @@ -285,7 +285,6 @@ const std::string Identifiers::ROBOT = "robot"; const std::string Identifiers::RW_VERSION_NAME = "rwversionname"; const std::string Identifiers::SINGLE = "single"; const std::string Identifiers::STATE = "state"; -const std::string Identifiers::STATUS = "status"; const std::string Identifiers::SYS = "sys"; const std::string Identifiers::SYS_OPTION_LI = "sys-option-li"; const std::string Identifiers::SYS_SYSTEM_LI = "sys-system-li"; @@ -294,16 +293,16 @@ const std::string Identifiers::TYPE = "type"; const std::string Identifiers::VALUE = "value"; const std::string Identifiers::CLASS = "class"; const std::string Identifiers::OPTION = "option"; +const std::string Queries::ACTION_LOAD_MODULE = "action=loadmod"; const std::string Queries::ACTION_RELEASE = "action=release"; const std::string Queries::ACTION_REQUEST = "action=request"; const std::string Queries::ACTION_RESETPP = "action=resetpp"; const std::string Queries::ACTION_SET = "action=set"; const std::string Queries::ACTION_SETCTRLSTATE = "action=setctrlstate"; -const std::string Queries::ACTION_SET_LEAD_THROUGH = "action=set-lead-through"; const std::string Queries::ACTION_SET_LOCALE = "action=set-locale"; const std::string Queries::ACTION_START = "action=start"; const std::string Queries::ACTION_STOP = "action=stop"; -const std::string Queries::RESOURCE_LEAD_THROUGH = "resource=lead-through"; +const std::string Queries::ACTION_UNLOAD_MODULE = "action=unloadmod"; const std::string Queries::TASK = "task="; const std::string Services::CTRL = "/ctrl"; const std::string Services::FILESERVICE = "/fileservice"; @@ -344,7 +343,6 @@ const XMLAttribute XMLAttributes::CLASS_RAP_MODULE_INFO_LI(Identifiers::CLASS, I const XMLAttribute XMLAttributes::CLASS_RAP_TASK_LI(Identifiers::CLASS , Identifiers::RAP_TASK_LI); const XMLAttribute XMLAttributes::CLASS_RW_VERSION_NAME(Identifiers::CLASS , Identifiers::RW_VERSION_NAME); const XMLAttribute XMLAttributes::CLASS_STATE(Identifiers::CLASS , Identifiers::STATE); -const XMLAttribute XMLAttributes::CLASS_STATUS(Identifiers::CLASS , Identifiers::STATUS); const XMLAttribute XMLAttributes::CLASS_SYS_OPTION_LI(Identifiers::CLASS , Identifiers::SYS_OPTION_LI); const XMLAttribute XMLAttributes::CLASS_SYS_SYSTEM_LI(Identifiers::CLASS , Identifiers::SYS_SYSTEM_LI); const XMLAttribute XMLAttributes::CLASS_TYPE(Identifiers::CLASS , Identifiers::TYPE); diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index d2ef3841..5a86635f 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -978,21 +978,14 @@ bool RWSInterface::getRAPIDSymbolData(const std::string& task, return rws_client_.getRAPIDSymbolData(RWSClient::RAPIDResource(task, symbol), p_data).success; } -bool RWSInterface::setLeadThroughOn(const std::string& mechunit) +bool RWSInterface::loadModuleIntoTask(const std::string& task, const RWSClient::FileResource& resource, const bool replace) { - return rws_client_.setLeadThrough(mechunit, Identifiers::ACTIVE).success; + return rws_client_.loadModuleIntoTask(task, resource, replace).success; } -bool RWSInterface::setLeadThroughOff(const std::string& mechunit) +bool RWSInterface::unloadModuleFromTask(const std::string& task, const RWSClient::FileResource& resource) { - return rws_client_.setLeadThrough(mechunit, Identifiers::INACTIVE).success; -} - -TriBool RWSInterface::isLeadThroughOn(const std::string& mechunit) -{ - return compareSingleContent(rws_client_.getLeadThrough(mechunit), - XMLAttributes::CLASS_STATUS, - ContollerStates::ACTIVE); + return rws_client_.unloadModuleFromTask(task, resource).success; } bool RWSInterface::getFile(const RWSClient::FileResource& resource, std::string* p_file_content) From 20985dde5dd0f42ce370c2999f022faf5809604d Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Tue, 26 Jan 2021 20:37:34 +0100 Subject: [PATCH 03/17] Squashed commit of the following: commit a61ee60fa333863c93125219f0e1344b86b75232 Author: Mikhail Katliar Date: Fri Jan 22 11:41:37 2021 +0100 Member functions in RWSClient made const and static where appropriate. commit 4ffd80090a9bb95f774c5609709df6a703e8cec5 Author: Mikhail Katliar Date: Tue Jan 19 17:19:52 2021 +0100 - Made RAPIDTaskExecutionState, MechanicalUnitType, and MechanicalUnitMode enum classes; - Added value_type in RAPIDAtomicTemplate; commit cf00d68c345e85ceb5fc4419c5195d77701de1c8 Author: Mikhail Katliar Date: Sat Jan 16 15:04:59 2021 +0100 Moved the Coordinate enum from the RWSClient class scope to the abb::rws namespace scope and made it an enum class. Passing Coordinate by value instead of by reference. commit 79e5e85e9dee9bc4876bc43dd22f5580dd48c0ea Author: Mikhail Katliar Date: Wed Dec 30 01:36:24 2020 +0100 * Added cast operator of atomic RAPID types to corresponding standard types. * Added override keyword in rws_rapid.h where appropriate. commit 0aca963f2333951f8d1d658546c933166f10ed82 Author: Mikhail Katliar Date: Sat Dec 26 15:29:13 2020 +0100 Added ZoneData class commit f0ff9944a28e08da733b3766eb7614bdb52f436e Author: Mikhail Katliar Date: Sat Dec 26 00:04:30 2020 +0100 Pulling out nested classes. --- include/abb_librws/rws_client.h | 433 +++++++------- include/abb_librws/rws_interface.h | 561 +++++++++--------- include/abb_librws/rws_rapid.h | 134 ++++- .../abb_librws/rws_state_machine_interface.h | 34 +- src/rws_client.cpp | 103 ++-- src/rws_interface.cpp | 118 ++-- src/rws_state_machine_interface.cpp | 1 - 7 files changed, 751 insertions(+), 633 deletions(-) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index a1b3743e..01a8641a 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -41,255 +41,264 @@ #include #include -#include "Poco/DOM/DOMParser.h" +#include #include "rws_common.h" #include "rws_rapid.h" #include "rws_poco_client.h" + namespace abb { namespace rws { /** - * \brief A class for a Robot Web Services (RWS) client based on a POCO client. - * - * Note: Only a subset of the features available in RWS are implemented here. - * - * See http://developercenter.robotstudio.com/webservice/api_reference for details about RWS. - * - * TODO: - * - Flesh out the subscription functionality. E.g. implement a "subscription manager". - * + * \brief A struct for containing an evaluated communication result. */ -class RWSClient : public POCOClient +struct RWSResult { -public: /** - * \brief A struct for containing an evaluated communication result. + * \brief For indicating if the communication was successfull or not. */ - struct RWSResult - { - /** - * \brief For indicating if the communication was successfull or not. - */ - bool success; + bool success; - /** - * \brief For containing any parsed result in XML format. If no data is parsed, then it will be null. - */ - Poco::AutoPtr p_xml_document; + /** + * \brief For containing any parsed result in XML format. If no data is parsed, then it will be null. + */ + Poco::AutoPtr p_xml_document; - /** - * \brief Container for an error message (if one occurred). - */ - std::string error_message; + /** + * \brief Container for an error message (if one occurred). + */ + std::string error_message; - /** - * \brief A default constructor. - */ - RWSResult() : success(false) {} - }; + /** + * \brief A default constructor. + */ + RWSResult() : success(false) {} +}; + +/** + * \brief A class for representing a RAPID symbol resource. + */ +struct RAPIDSymbolResource +{ /** - * \brief A class for representing a RAPID symbol resource. + * \brief A constructor. + * + * \param module specifying the name of the RAPID module containing the symbol. + * \param name specifying the name of the RAPID symbol. */ - struct RAPIDSymbolResource - { - /** - * \brief A constructor. - * - * \param module specifying the name of the RAPID module containing the symbol. - * \param name specifying the name of the RAPID symbol. - */ - RAPIDSymbolResource(const std::string& module, const std::string& name) - : - module(module), - name(name) - {} + RAPIDSymbolResource(const std::string& module, const std::string& name) + : + module(module), + name(name) + {} - /** - * \brief The RAPID module name. - */ - std::string module; + /** + * \brief The RAPID module name. + */ + std::string module; + + /** + * \brief The RAPID symbol name. + */ + std::string name; +}; - /** - * \brief The RAPID symbol name. - */ - std::string name; - }; +/** + * \brief A class for representing a RAPID resource. + */ +struct RAPIDResource +{ /** - * \brief A class for representing a RAPID resource. + * \brief A constructor. + * + * \param task specifying the name of the RAPID task containing the symbol. + * \param module specifying the name of the RAPID module containing the symbol. + * \param name specifying the name of the RAPID symbol. */ - struct RAPIDResource - { - /** - * \brief A constructor. - * - * \param task specifying the name of the RAPID task containing the symbol. - * \param module specifying the name of the RAPID module containing the symbol. - * \param name specifying the name of the RAPID symbol. - */ - RAPIDResource(const std::string& task, const std::string& module, const std::string& name) - : - task(task), - module(module), - name(name) - {} + RAPIDResource(const std::string& task, const std::string& module, const std::string& name) + : + task(task), + module(module), + name(name) + {} - /** - * \brief A constructor. - * - * \param task specifying the name of the RAPID task containing the symbol. - * \param symbol specifying the names of the RAPID module and the the symbol. - */ - RAPIDResource(const std::string& task, const RAPIDSymbolResource& symbol) - : - task(task), - module(symbol.module), - name(symbol.name) - {} + /** + * \brief A constructor. + * + * \param task specifying the name of the RAPID task containing the symbol. + * \param symbol specifying the names of the RAPID module and the the symbol. + */ + RAPIDResource(const std::string& task, const RAPIDSymbolResource& symbol) + : + task(task), + module(symbol.module), + name(symbol.name) + {} - /** - * \brief The RAPID task name. - */ - std::string task; + /** + * \brief The RAPID task name. + */ + std::string task; - /** - * \brief The RAPID module name. - */ - std::string module; + /** + * \brief The RAPID module name. + */ + std::string module; + + /** + * \brief The RAPID symbol name. + */ + std::string name; +}; - /** - * \brief The RAPID symbol name. - */ - std::string name; - }; +/** + * \brief A class for representing a file resource. + */ +struct FileResource +{ /** - * \brief A class for representing a file resource. + * \brief A constructor. + * + * \param filename specifying the name of the file. + * \param directory specifying the directory of the file on the robot controller (set to $home by default). */ - struct FileResource - { - /** - * \brief A constructor. - * - * \param filename specifying the name of the file. - * \param directory specifying the directory of the file on the robot controller (set to $home by default). - */ - FileResource(const std::string& filename, - const std::string& directory = SystemConstants::RWS::Identifiers::HOME_DIRECTORY) - : - filename(filename), - directory(directory) - {} + FileResource(const std::string& filename, + const std::string& directory = SystemConstants::RWS::Identifiers::HOME_DIRECTORY) + : + filename(filename), + directory(directory) + {} - /** - * \brief The file's name. - */ - std::string filename; + /** + * \brief The file's name. + */ + std::string filename; - /** - * \brief The file's directory on the robot controller. - */ - std::string directory; - }; + /** + * \brief The file's directory on the robot controller. + */ + std::string directory; +}; + +/** + * \brief An enum for specifying subscription priority. + */ +enum SubscriptionPriority +{ + LOW, ///< Low priority. + MEDIUM, ///< Medium priority. + HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. +}; + + +/** + * \brief A struct for containing information about a subscription resource. + */ +struct SubscriptionResource +{ /** - * \brief A class for representing subscription resources. + * \brief URI of the resource. */ - class SubscriptionResources - { - public: - /** - * \brief An enum for specifying subscription priority. - */ - enum Priority - { - LOW, ///< Low priority. - MEDIUM, ///< Medium priority. - HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. - }; + std::string resource_uri; - /** - * \brief A struct for containing information about a subscription resource. - */ - struct SubscriptionResource - { - /** - * \brief URI of the resource. - */ - std::string resource_uri; - - /** - * \brief Priority of the subscription. - */ - Priority priority; - - /** - * \brief A constructor. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - SubscriptionResource(const std::string& resource_uri, const Priority priority) - : - resource_uri(resource_uri), - priority(priority) - {} - }; + /** + * \brief Priority of the subscription. + */ + SubscriptionPriority priority; - /** - * \brief A method to add information about a subscription resource. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - void add(const std::string& resource_uri, const Priority priority); + /** + * \brief A constructor. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + SubscriptionResource(const std::string& resource_uri, const SubscriptionPriority priority) + : + resource_uri(resource_uri), + priority(priority) + {} +}; - /** - * \brief A method to add information about a IO signal subscription resource. - * - * \param iosignal for the IO signal's name. - * \param priority for the priority of the subscription. - */ - void addIOSignal(const std::string& iosignal, const Priority priority); - /** - * \brief A method to add information about a RAPID persistant symbol subscription resource. - * - * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. - * \param priority for the priority of the subscription. - */ - void addRAPIDPersistantVariable(const RAPIDResource& resource, const Priority priority); +/** + * \brief A class for representing subscription resources. + */ +class SubscriptionResources +{ +public: + /** + * \brief A method to add information about a subscription resource. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + void add(const std::string& resource_uri, const SubscriptionPriority priority); - /** - * \brief A method for retrieving the contained subscription resources information. - * - * \return std::vector containing information of the subscription resources. - */ - const std::vector& getResources() const { return resources_; } + /** + * \brief A method to add information about a IO signal subscription resource. + * + * \param iosignal for the IO signal's name. + * \param priority for the priority of the subscription. + */ + void addIOSignal(const std::string& iosignal, const SubscriptionPriority priority); - private: - /** - * \brief A vector of subscription resources. - */ - std::vector resources_; - }; + /** + * \brief A method to add information about a RAPID persistant symbol subscription resource. + * + * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. + * \param priority for the priority of the subscription. + */ + void addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority); /** - * \brief An enumeration of controller coordinate frames. + * \brief A method for retrieving the contained subscription resources information. + * + * \return std::vector containing information of the subscription resources. */ - enum Coordinate - { - BASE, ///< \brief Base frame coordinate. - WORLD, ///< \brief World frame coordinate. - TOOL, ///< \brief Tool frame coordinate. - WOBJ, ///< \brief Work object (wobj) frame coordinate. - ACTIVE ///< \brief Currently active coordinate. - }; + const std::vector& getResources() const { return resources_; } + +private: + /** + * \brief A vector of subscription resources. + */ + std::vector resources_; +}; + + +/** + * \brief An enumeration of controller coordinate frames. + */ +enum class Coordinate +{ + BASE, ///< \brief Base frame coordinate. + WORLD, ///< \brief World frame coordinate. + TOOL, ///< \brief Tool frame coordinate. + WOBJ, ///< \brief Work object (wobj) frame coordinate. + ACTIVE ///< \brief Currently active coordinate. +}; + +/** + * \brief A class for a Robot Web Services (RWS) client based on a POCO client. + * + * Note: Only a subset of the features available in RWS are implemented here. + * + * See http://developercenter.robotstudio.com/webservice/api_reference for details about RWS. + * + * TODO: + * - Flesh out the subscription functionality. E.g. implement a "subscription manager". + * + */ +class RWSClient : public POCOClient +{ +public: /** * \brief A constructor. * @@ -430,7 +439,7 @@ class RWSClient : public POCOClient * \return RWSResult containing the result. */ RWSResult getMechanicalUnitRobTarget(const std::string& mechunit, - const Coordinate& coordinate = ACTIVE, + const Coordinate& coordinate = Coordinate::ACTIVE, const std::string& tool = "", const std::string& wobj = ""); @@ -700,7 +709,7 @@ class RWSClient : public POCOClient * \param result containing the result of the parsing. * \param poco_result containing the POCO result. */ - void parseMessage(RWSResult* result, const POCOResult& poco_result); + static void parseMessage(RWSResult* result, const POCOResult& poco_result); /** * \brief Method for retrieving the internal log as a text string. @@ -709,7 +718,7 @@ class RWSClient : public POCOClient * * \return std::string containing the log text. An empty text string is returned if the log is empty. */ - std::string getLogText(const bool verbose = false); + std::string getLogText(const bool verbose = false) const; /** * \brief Method for retrieving only the most recently logged event as a text string. @@ -718,7 +727,7 @@ class RWSClient : public POCOClient * * \return std::string containing the log text. An empty text string is returned if the log is empty. */ - std::string getLogTextLatestEvent(const bool verbose = false); + std::string getLogTextLatestEvent(const bool verbose = false) const; private: /** @@ -778,7 +787,7 @@ class RWSClient : public POCOClient * * \return std::string containing the path. */ - std::string generateConfigurationPath(const std::string& topic, const std::string& type); + static std::string generateConfigurationPath(const std::string& topic, const std::string& type); /** * \brief Method for generating an IO signal URI path. @@ -787,7 +796,7 @@ class RWSClient : public POCOClient * * \return std::string containing the path. */ - std::string generateIOSignalPath(const std::string& iosignal); + static std::string generateIOSignalPath(const std::string& iosignal); /** * \brief Method for generating a mechanical unit resource URI path. @@ -796,7 +805,7 @@ class RWSClient : public POCOClient * * \return std::string containing the path. */ - std::string generateMechanicalUnitPath(const std::string& mechunit); + static std::string generateMechanicalUnitPath(const std::string& mechunit); /** * \brief Method for generating a RAPID data resource URI path. @@ -805,7 +814,7 @@ class RWSClient : public POCOClient * * \return std::string containing the path. */ - std::string generateRAPIDDataPath(const RAPIDResource& resource); + static std::string generateRAPIDDataPath(const RAPIDResource& resource); /** * \brief Method for generating a RAPID properties resource URI path. @@ -814,7 +823,7 @@ class RWSClient : public POCOClient * * \return std::string containing the path. */ - std::string generateRAPIDPropertiesPath(const RAPIDResource& resource); + static std::string generateRAPIDPropertiesPath(const RAPIDResource& resource); /** * \brief Method for generating a file resource URI path. @@ -823,7 +832,7 @@ class RWSClient : public POCOClient * * \return std::string containing the path. */ - std::string generateFilePath(const FileResource& resource); + static std::string generateFilePath(const FileResource& resource); /** * \brief Static constant for the log's size. diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 26806709..fc1dfd25 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -44,306 +44,309 @@ namespace abb { namespace rws { + /** - * \brief A class for wrapping a Robot Web Services (RWS) client in a more user friendly interface. +* \brief Execution state of a RAPID task. +*/ +enum class RAPIDTaskExecutionState +{ + UNKNOWN, ///< The task state is unknown. + READY, ///< The task is ready. + STOPPED, ///< The task has been stopped. + STARTED, ///< The task has been started. + UNINITIALIZED ///< The task has not been initialized. +}; + +/** + * \brief Type of a mechanical unit. */ -class RWSInterface +enum class MechanicalUnitType +{ + NONE, ///< The unit has no type. + TCP_ROBOT, ///< The unit is a TCP robot (has more than one joint, and can process commands in Cartesian space). + ROBOT, ///< The unit is a robot (has more than one joint, but can only process commands in joint space). + SINGLE, ///< The unit is a single (has only one joint). + UNDEFINED ///< The unit is undefined. +}; + +/** + * \brief Mode of a mechanical unit. + */ +enum class MechanicalUnitMode +{ + UNKNOWN_MODE, ///< The unit mode is unknown. + ACTIVATED, ///< The unit has been activated. + DEACTIVATED ///< The unit has been deactivated. +}; + +/** + * \brief A struct for containing static information of a mechanical unit. + */ +struct MechanicalUnitStaticInfo { -public: /** - * \brief Execution state of a RAPID task. + * \brief The unit's type. */ - enum RAPIDTaskExecutionState - { - UNKNOWN, ///< The task state is unknown. - READY, ///< The task is ready. - STOPPED, ///< The task has been stopped. - STARTED, ///< The task has been started. - UNINITIALIZED ///< The task has not been initialized. - }; + MechanicalUnitType type; /** - * \brief Type of a mechanical unit. + * \brief The RAPID task using the unit. */ - enum MechanicalUnitType - { - NONE, ///< The unit has no type. - TCP_ROBOT, ///< The unit is a TCP robot (has more than one joint, and can process commands in Cartesian space). - ROBOT, ///< The unit is a robot (has more than one joint, but can only process commands in joint space). - SINGLE, ///< The unit is a single (has only one joint). - UNDEFINED ///< The unit is undefined. - }; + std::string task_name; /** - * \brief Mode of a mechanical unit. + * \brief Number of axes in the unit. */ - enum MechanicalUnitMode - { - UNKNOWN_MODE, ///< The unit mode is unknown. - ACTIVATED, ///< The unit has been activated. - DEACTIVATED ///< The unit has been deactivated. - }; + int axes; /** - * \brief A struct for containing static information of a mechanical unit. + * \brief Total number of axes in the unit (including axes in possible integrated unit). */ - struct MechanicalUnitStaticInfo - { - /** - * \brief The unit's type. - */ - MechanicalUnitType type; - - /** - * \brief The RAPID task using the unit. - */ - std::string task_name; - - /** - * \brief Number of axes in the unit. - */ - int axes; - - /** - * \brief Total number of axes in the unit (including axes in possible integrated unit). - */ - int axes_total; - - /** - * \brief Name of another unit (that this unit is integrated into). - * - * Will be set to "NoIntegratedUnit" if this unit is not integrated into another unit. - */ - std::string is_integrated_unit; - - /** - * \brief Name of another unit (that is part of this unit). - * - * Will be set to "NoIntegratedUnit" if this unit has no integrated unit. - */ - std::string has_integrated_unit; - }; - - /** - * \brief A struct for containing dynamic information of a mechanical unit. - */ - struct MechanicalUnitDynamicInfo - { - /** - * \brief Name of the unit's active tool. - */ - std::string tool_name; - - /** - * \brief Name of the unit's active work object. - */ - std::string wobj_name; - - /** - * \brief Name of the unit's active payload. - */ - std::string payload_name; - - /** - * \brief Name of the unit's active total payload. - */ - std::string total_payload_name; - - /** - * \brief The unit's current state. - */ - std::string status; - - /** - * \brief The unit's current mode. - */ - MechanicalUnitMode mode; - - /** - * \brief The unit's current jogging mode. - */ - std::string jog_mode; - - /** - * \brief The unit's current coordinate system type. - */ - RWSClient::Coordinate coord_system; - }; - - /** - * \brief A struct for containing system information of the robot controller. - */ - struct SystemInfo - { - /** - * \brief The RobotWare version name. - */ - std::string robot_ware_version; + int axes_total; - /** - * \brief The system's name. - */ - std::string system_name; + /** + * \brief Name of another unit (that this unit is integrated into). + * + * Will be set to "NoIntegratedUnit" if this unit is not integrated into another unit. + */ + std::string is_integrated_unit; - /** - * \brief The system's type (e.g. if it is a virtual controller system or not). - */ - std::string system_type; + /** + * \brief Name of another unit (that is part of this unit). + * + * Will be set to "NoIntegratedUnit" if this unit has no integrated unit. + */ + std::string has_integrated_unit; +}; - /** - * \brief The system's options. - */ - std::vector system_options; - }; +/** + * \brief A struct for containing dynamic information of a mechanical unit. + */ +struct MechanicalUnitDynamicInfo +{ + /** + * \brief Name of the unit's active tool. + */ + std::string tool_name; /** - * \brief A struct for containing information about a RobotWare option. + * \brief Name of the unit's active work object. */ - struct RobotWareOptionInfo - { - /** - * \brief A constructor. - * - * \param name for the name of the option. - * \param description for the description of the option. - */ - RobotWareOptionInfo(const std::string& name, const std::string& description) - : - name(name), - description(description) - {} - - /** - * \brief The option's name. - */ - std::string name; - - /** - * \brief The options's description. - */ - std::string description; - }; - - /** - * \brief A struct for containing information about a RAPID module. - */ - struct RAPIDModuleInfo - { - /** - * \brief A constructor. - * - * \param name for the name of the module. - * \param type for the type of the module. - */ - RAPIDModuleInfo(const std::string& name, const std::string& type) - : - name(name), - type(type) - {} - - /** - * \brief The module's name. - */ - std::string name; - - /** - * \brief The module's type. - */ - std::string type; - }; - - /** - * \brief A struct for containing information about a RAPID task. - */ - struct RAPIDTaskInfo - { - /** - * \brief A constructor. - * - * \param name for the name of the task. - * \param is_motion_task indicating if the task is a motion task or not. - * \param is_active indicating if the task is active or not. - * \param execution_state indicating the task's current execution state. - */ - RAPIDTaskInfo(const std::string& name, - const bool is_motion_task, - const bool is_active, - const RAPIDTaskExecutionState execution_state) - : - name(name), - is_motion_task(is_motion_task), - is_active(is_active), - execution_state(execution_state) - {} - - /** - * \brief The task's name. - */ - std::string name; - - /** - * \brief Flag indicating if the task is a motion task. - */ - bool is_motion_task; - - /** - * \brief Flag indicating if the task is active or not. - */ - bool is_active; - - /** - * \brief The current execution state of the task. - */ - RAPIDTaskExecutionState execution_state; - }; - - /** - * \brief A struct for containing static information (at least during runtime) about the robot controller. - */ - struct StaticInfo - { - /** - * \brief Information about the defined RAPID tasks. - */ - std::vector rapid_tasks; + std::string wobj_name; - /** - * \brief System information. - */ - SystemInfo system_info; - }; + /** + * \brief Name of the unit's active payload. + */ + std::string payload_name; /** - * \brief A struct for containing runtime information about the robot controller. + * \brief Name of the unit's active total payload. */ - struct RuntimeInfo - { - /** - * \brief A default constructor. - */ - RuntimeInfo() : rws_connected(false) {} + std::string total_payload_name; + + /** + * \brief The unit's current state. + */ + std::string status; + + /** + * \brief The unit's current mode. + */ + MechanicalUnitMode mode; + + /** + * \brief The unit's current jogging mode. + */ + std::string jog_mode; + + /** + * \brief The unit's current coordinate system type. + */ + Coordinate coord_system; +}; + +/** + * \brief A struct for containing system information of the robot controller. + */ +struct SystemInfo +{ + /** + * \brief The RobotWare version name. + */ + std::string robot_ware_version; + + /** + * \brief The system's name. + */ + std::string system_name; + + /** + * \brief The system's type (e.g. if it is a virtual controller system or not). + */ + std::string system_type; + + /** + * \brief The system's options. + */ + std::vector system_options; +}; + +/** + * \brief A struct for containing information about a RobotWare option. + */ +struct RobotWareOptionInfo +{ + /** + * \brief A constructor. + * + * \param name for the name of the option. + * \param description for the description of the option. + */ + RobotWareOptionInfo(const std::string& name, const std::string& description) + : + name(name), + description(description) + {} + + /** + * \brief The option's name. + */ + std::string name; + + /** + * \brief The options's description. + */ + std::string description; +}; + +/** + * \brief A struct for containing information about a RAPID module. + */ +struct RAPIDModuleInfo +{ + /** + * \brief A constructor. + * + * \param name for the name of the module. + * \param type for the type of the module. + */ + RAPIDModuleInfo(const std::string& name, const std::string& type) + : + name(name), + type(type) + {} + + /** + * \brief The module's name. + */ + std::string name; + + /** + * \brief The module's type. + */ + std::string type; +}; + +/** + * \brief A struct for containing information about a RAPID task. + */ +struct RAPIDTaskInfo +{ + /** + * \brief A constructor. + * + * \param name for the name of the task. + * \param is_motion_task indicating if the task is a motion task or not. + * \param is_active indicating if the task is active or not. + * \param execution_state indicating the task's current execution state. + */ + RAPIDTaskInfo(const std::string& name, + const bool is_motion_task, + const bool is_active, + const RAPIDTaskExecutionState execution_state) + : + name(name), + is_motion_task(is_motion_task), + is_active(is_active), + execution_state(execution_state) + {} + + /** + * \brief The task's name. + */ + std::string name; + + /** + * \brief Flag indicating if the task is a motion task. + */ + bool is_motion_task; + + /** + * \brief Flag indicating if the task is active or not. + */ + bool is_active; + + /** + * \brief The current execution state of the task. + */ + RAPIDTaskExecutionState execution_state; +}; + + +/** + * \brief A struct for containing static information (at least during runtime) about the robot controller. + */ +struct StaticInfo +{ + /** + * \brief Information about the defined RAPID tasks. + */ + std::vector rapid_tasks; + + /** + * \brief System information. + */ + SystemInfo system_info; +}; - /** - * \brief Indicator for if the mode is auto or not or unknown. - */ - TriBool auto_mode; +/** + * \brief A struct for containing runtime information about the robot controller. + */ +struct RuntimeInfo +{ + /** + * \brief A default constructor. + */ + RuntimeInfo() : rws_connected(false) {} - /** - * \brief Indicator for if the motors are on or not or unknown. - */ - TriBool motors_on; + /** + * \brief Indicator for if the mode is auto or not or unknown. + */ + TriBool auto_mode; - /** - * \brief Indicator for if RAPID is running or not or unknown. - */ - TriBool rapid_running; + /** + * \brief Indicator for if the motors are on or not or unknown. + */ + TriBool motors_on; - /** - * \brief Indicator for if RWS is connected to the robot controller system. - */ - bool rws_connected; - }; + /** + * \brief Indicator for if RAPID is running or not or unknown. + */ + TriBool rapid_running; + /** + * \brief Indicator for if RWS is connected to the robot controller system. + */ + bool rws_connected; +}; + + +/** + * \brief A class for wrapping a Robot Web Services (RWS) client in a more user friendly interface. + */ +class RWSInterface +{ +public: /** * \brief A constructor. * @@ -552,7 +555,7 @@ class RWSInterface */ bool getMechanicalUnitRobTarget(const std::string& mechunit, RobTarget* p_robtarget, - const RWSClient::Coordinate& coordinate = RWSClient::ACTIVE, + Coordinate coordinate = Coordinate::ACTIVE, const std::string& tool = "", const std::string& wobj = ""); @@ -594,7 +597,7 @@ class RWSInterface * \return bool indicating if the communication was successful or not. Note: No checks are made for "correct parsing". */ bool getRAPIDSymbolData(const std::string& task, - const RWSClient::RAPIDSymbolResource& symbol, + const RAPIDSymbolResource& symbol, RAPIDSymbolDataAbstract* p_data); /** @@ -713,7 +716,7 @@ class RWSInterface * \return bool indicating if the communication was successful or not. */ bool setRAPIDSymbolData(const std::string& task, - const RWSClient::RAPIDSymbolResource& symbol, + const RAPIDSymbolResource& symbol, const RAPIDSymbolDataAbstract& data); /** @@ -772,7 +775,7 @@ class RWSInterface * * \return bool indicating if the communication was successful or not. */ - bool getFile(const RWSClient::FileResource& resource, std::string* p_file_content); + bool getFile(const FileResource& resource, std::string* p_file_content); /** * \brief A method for uploading a file to the robot controller. @@ -782,7 +785,7 @@ class RWSInterface * * \return bool indicating if the communication was successful or not. */ - bool uploadFile(const RWSClient::FileResource& resource, const std::string& file_content); + bool uploadFile(const FileResource& resource, const std::string& file_content); /** * \brief A method for deleting a file from the robot controller. @@ -791,7 +794,7 @@ class RWSInterface * * \return bool indicating if the communication was successful or not. */ - bool deleteFile(const RWSClient::FileResource& resource); + bool deleteFile(const FileResource& resource); /** * \brief A method for starting for a subscription. @@ -800,7 +803,7 @@ class RWSInterface * * \return bool indicating if the communication was successful or not. */ - bool startSubscription(const RWSClient::SubscriptionResources& resources); + bool startSubscription(const SubscriptionResources& resources); /** * \brief A method for waiting for a subscription event (use if the event content is irrelevant). @@ -903,7 +906,7 @@ class RWSInterface * * \return TriBool containing the result of the comparison. */ - TriBool compareSingleContent(const RWSClient::RWSResult& rws_result, + TriBool compareSingleContent(const RWSResult& rws_result, const XMLAttribute& attribute, const std::string& compare_string); diff --git a/include/abb_librws/rws_rapid.h b/include/abb_librws/rws_rapid.h index 593c205b..15f0d7a8 100644 --- a/include/abb_librws/rws_rapid.h +++ b/include/abb_librws/rws_rapid.h @@ -93,17 +93,33 @@ template struct RAPIDAtomicTemplate : public RAPIDSymbolDataAbstract { public: + /** + * \brief Type of contained value. + */ + using value_type = T; + + /** * \brief A method for parsing a RAPID symbol data value string. * * \param value_string containing the string to parse. */ - void parseString(const std::string& value_string) + void parseString(const std::string& value_string) override { std::stringstream ss(value_string); ss >> value; } + + /** + * \brief Conversion to a standard data type. + */ + operator T const&() const + { + return value; + } + + /** * \brief Container for the data's value. */ @@ -141,21 +157,21 @@ struct RAPIDAtomic : public RAPIDAtomicTemplate * * \return std::string containing the data type name. */ - std::string getType() const; + std::string getType() const override; /** * \brief A method for parsing a RAPID symbol data value string. * * \param value_string containing the string to parse. */ - void parseString(const std::string& value_string); + void parseString(const std::string& value_string) override; /** * \brief A method for constructing a RAPID symbol data value string. * * \return std::string containing the constructed string. */ - std::string constructString() const; + std::string constructString() const override; }; /** @@ -176,14 +192,14 @@ struct RAPIDAtomic : public RAPIDAtomicTemplate * * \return std::string containing the data type name. */ - std::string getType() const; + std::string getType() const override; /** * \brief A method for constructing a RAPID symbol data value string. * * \return std::string containing the constructed string. */ - std::string constructString() const; + std::string constructString() const override; }; /** @@ -204,14 +220,14 @@ struct RAPIDAtomic : public RAPIDAtomicTemplate * * \return std::string containing the data type name. */ - std::string getType() const; + std::string getType() const override; /** * \brief A method for constructing a RAPID symbol data value string. * * \return std::string containing the constructed string. */ - std::string constructString() const; + std::string constructString() const override; }; /** @@ -232,21 +248,21 @@ struct RAPIDAtomic : public RAPIDAtomicTemplate * * \return std::string containing the data type name. */ - std::string getType() const; + std::string getType() const override; /** * \brief A method for parsing a RAPID symbol data value string. * * \param value_string containing the string to parse. */ - void parseString(const std::string& value_string); + void parseString(const std::string& value_string) override; /** * \brief A method for constructing a RAPID symbol data value string. * * \return std::string containing the constructed string. */ - std::string constructString() const; + std::string constructString() const override; }; /** @@ -287,21 +303,21 @@ struct RAPIDRecord : public RAPIDSymbolDataAbstract * * \return std::string containing the constructed string. */ - std::string constructString() const; + std::string constructString() const override; /** * \brief A method for parsing a RAPID symbol data value string. * * \param value_string containing the string to parse. */ - void parseString(const std::string& value_string); + void parseString(const std::string& value_string) override; /** * \brief A method for getting the type of the RAPID record. * * \return std::string containing the type. */ - std::string getType() const; + std::string getType() const override; /** * \brief Operator for copying the RAPID record to another RAPID record. @@ -963,6 +979,96 @@ struct SpeedData : public RAPIDRecord RAPIDNum v_reax; }; + +/** + * \brief A struct, for representing a RAPID zonedata record. + */ +struct ZoneData : public RAPIDRecord +{ +public: + /** + * \brief A default constructor. + */ + ZoneData() + : + RAPIDRecord("zonedata") + { + components_.push_back(&finep); + components_.push_back(&pzone_tcp); + components_.push_back(&pzone_ori); + components_.push_back(&pzone_eax); + components_.push_back(&zone_ori); + components_.push_back(&zone_leax); + components_.push_back(&zone_reax); + } + + /** + * \brief Copy constructor. + * + * \param other containing the values to copy. + */ + ZoneData(const ZoneData& other) + : RAPIDRecord(other.record_type_name_) + , finep {other.finep} + , pzone_tcp {other.pzone_tcp} + , pzone_ori {other.pzone_ori} + , pzone_eax {other.pzone_eax} + , zone_ori {other.zone_ori} + , zone_leax {other.zone_leax} + , zone_reax {other.zone_reax} + { + components_.clear(); + components_.push_back(&finep); + components_.push_back(&pzone_tcp); + components_.push_back(&pzone_ori); + components_.push_back(&pzone_eax); + components_.push_back(&zone_ori); + components_.push_back(&zone_leax); + components_.push_back(&zone_reax); + } + + /** + * \brief Defines whether the movement is to terminate as a stop point (fine point) or as a fly-by point. + */ + RAPIDBool finep; + + /** + * \brief The size (the radius) of the TCP zone in mm. + */ + RAPIDNum pzone_tcp; + + /** + * \brief The zone size (the radius) for the tool reorientation. + * + * The size is defined as the distance of the TCP from the programmed point in mm. + */ + RAPIDNum pzone_ori; + + /** + * \brief The zone size (the radius) for external axes. + * + * The size is defined as the distance of the TCP from the programmed point in mm. + */ + RAPIDNum pzone_eax; + + /** + * \brief The zone size for the tool reorientation in degrees. + * + * If the robot is holding the work object, this means an angle of rotation for the work object. + */ + RAPIDNum zone_ori; + + /** + * \brief The zone size for linear external axes in mm. + */ + RAPIDNum zone_leax; + + /** + * \brief The zone size for rotating external axes in degrees. + */ + RAPIDNum zone_reax; +}; + } // end namespace rws } // end namespace abb diff --git a/include/abb_librws/rws_state_machine_interface.h b/include/abb_librws/rws_state_machine_interface.h index c8cb8703..9279b0de 100644 --- a/include/abb_librws/rws_state_machine_interface.h +++ b/include/abb_librws/rws_state_machine_interface.h @@ -282,96 +282,96 @@ class RWSStateMachineInterface : public RWSInterface * * Note: Requires that the EGM option exists in the controller system. */ - static const RWSClient::RAPIDSymbolResource EGM_CURRENT_ACTION; + static const RAPIDSymbolResource EGM_CURRENT_ACTION; /** * \brief RAPID symbol containing settings to different EGM RAPID instructions. * * Note: Requires that the EGM option exists in the controller system. */ - static const RWSClient::RAPIDSymbolResource EGM_SETTINGS; + static const RAPIDSymbolResource EGM_SETTINGS; /** * \brief RAPID symbol indicating the current state of a RAPID motion task. */ - static const RWSClient::RAPIDSymbolResource MAIN_CURRENT_STATE; + static const RAPIDSymbolResource MAIN_CURRENT_STATE; /** * \brief RAPID symbol containing name input to the predefined routine "runCallByVar". */ - static const RWSClient::RAPIDSymbolResource RAPID_CALL_BY_VAR_NAME_INPUT; + static const RAPIDSymbolResource RAPID_CALL_BY_VAR_NAME_INPUT; /** * \brief RAPID symbol containing number input to the predefined routine "runCallByVar". */ - static const RWSClient::RAPIDSymbolResource RAPID_CALL_BY_VAR_NUM_INPUT; + static const RAPIDSymbolResource RAPID_CALL_BY_VAR_NUM_INPUT; /** * \brief RAPID symbol containing module file path input to the predefined routines * "runModuleLoad" and "runModuleUnload". */ - static const RWSClient::RAPIDSymbolResource RAPID_MODULE_FILE_PATH_INPUT; + static const RAPIDSymbolResource RAPID_MODULE_FILE_PATH_INPUT; /** * \brief RAPID symbol containing jointtarget input to the predefined routine "runMoveAbsJ". */ - static const RWSClient::RAPIDSymbolResource RAPID_MOVE_JOINT_TARGET_INPUT; + static const RAPIDSymbolResource RAPID_MOVE_JOINT_TARGET_INPUT; /** * \brief RAPID symbol containing robtarget input to the predefined routine "runMoveJ". */ - static const RWSClient::RAPIDSymbolResource RAPID_MOVE_ROB_TARGET_INPUT; + static const RAPIDSymbolResource RAPID_MOVE_ROB_TARGET_INPUT; /** * \brief RAPID symbol containing speed input to the predefined routines "runMoveAbsJ" and "runMoveJ". */ - static const RWSClient::RAPIDSymbolResource RAPID_MOVE_SPEED_INPUT; + static const RAPIDSymbolResource RAPID_MOVE_SPEED_INPUT; /** * \brief RAPID symbol containing routine name input specifying a RAPID routine to run. */ - static const RWSClient::RAPIDSymbolResource RAPID_ROUTINE_NAME_INPUT; + static const RAPIDSymbolResource RAPID_ROUTINE_NAME_INPUT; /** * \brief RAPID symbol containing command input for specifying the desired gripper command. * * Note: Requires that the SmartGripper product exists in the controller system. */ - static const RWSClient::RAPIDSymbolResource SG_COMMAND_INPUT; + static const RAPIDSymbolResource SG_COMMAND_INPUT; /** * \brief RAPID symbol containing settings to different SmartGripper RAPID instructions. * * Note: Requires that the SmartGripper product exists in the controller system. */ - static const RWSClient::RAPIDSymbolResource SG_SETTINGS; + static const RAPIDSymbolResource SG_SETTINGS; /** * \brief RAPID symbol containing position input for specifying the position a SmartGripper should move to. * * Note: Requires that the SmartGripper product exists in the controller system. */ - static const RWSClient::RAPIDSymbolResource SG_TARGET_POSTION_INPUT; + static const RAPIDSymbolResource SG_TARGET_POSTION_INPUT; /** * \brief RAPID symbol containing base frame extracted during initialization, for a RAPID motion task. */ - static const RWSClient::RAPIDSymbolResource UTILITY_BASE_FRAME; + static const RAPIDSymbolResource UTILITY_BASE_FRAME; /** * \brief RAPID symbol containing calibration target extracted during initialization, for a RAPID motion task. */ - static const RWSClient::RAPIDSymbolResource UTILITY_CALIBRATION_TARGET; + static const RAPIDSymbolResource UTILITY_CALIBRATION_TARGET; /** * \brief RAPID symbol indicating if a watchdog is active or not. */ - static const RWSClient::RAPIDSymbolResource WATCHDOG_ACTIVE; + static const RAPIDSymbolResource WATCHDOG_ACTIVE; /** * \brief RAPID symbol indicating if a watchdog should check an external status signal or not. */ - static const RWSClient::RAPIDSymbolResource WATCHDOG_CHECK_EXTERNAL_STATUS; + static const RAPIDSymbolResource WATCHDOG_CHECK_EXTERNAL_STATUS; }; }; }; diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 256caf70..a4b0f38f 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -37,9 +37,10 @@ #include #include -#include "Poco/SAX/InputSource.h" +#include + +#include -#include "abb_librws/rws_client.h" namespace { @@ -59,14 +60,14 @@ typedef SystemConstants::RWS::Services Services; typedef SystemConstants::RWS::XMLAttributes XMLAttributes; /*********************************************************************************************************************** - * Class definitions: RWSClient::SubscriptionResources + * Class definitions: SubscriptionResources */ /************************************************************ * Primary methods */ -void RWSClient::SubscriptionResources::addIOSignal(const std::string& iosignal, const Priority priority) +void SubscriptionResources::addIOSignal(const std::string& iosignal, const SubscriptionPriority priority) { std::string resource_uri = Resources::RW_IOSYSTEM_SIGNALS; resource_uri += "/"; @@ -77,8 +78,8 @@ void RWSClient::SubscriptionResources::addIOSignal(const std::string& iosignal, add(resource_uri, priority); } -void RWSClient::SubscriptionResources::addRAPIDPersistantVariable(const RAPIDResource& resource, - const Priority priority) +void SubscriptionResources::addRAPIDPersistantVariable(const RAPIDResource& resource, + const SubscriptionPriority priority) { std::string resource_uri = Resources::RW_RAPID_SYMBOL_DATA_RAPID; resource_uri += "/"; @@ -93,7 +94,7 @@ void RWSClient::SubscriptionResources::addRAPIDPersistantVariable(const RAPIDRes add(resource_uri, priority); } -void RWSClient::SubscriptionResources::add(const std::string& resource_uri, const Priority priority) +void SubscriptionResources::add(const std::string& resource_uri, const SubscriptionPriority priority) { resources_.push_back(SubscriptionResource(resource_uri, priority)); } @@ -109,7 +110,7 @@ void RWSClient::SubscriptionResources::add(const std::string& resource_uri, cons * Primary methods */ -RWSClient::RWSResult RWSClient::getContollerService() +RWSResult RWSClient::getContollerService() { std::string uri = Services::CTRL; @@ -120,7 +121,7 @@ RWSClient::RWSResult RWSClient::getContollerService() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getConfigurationInstances(const std::string& topic, const std::string& type) +RWSResult RWSClient::getConfigurationInstances(const std::string& topic, const std::string& type) { std::string uri = generateConfigurationPath(topic, type) + Resources::INSTANCES; @@ -131,7 +132,7 @@ RWSClient::RWSResult RWSClient::getConfigurationInstances(const std::string& top return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getIOSignals() +RWSResult RWSClient::getIOSignals() { std::string const & uri = SystemConstants::RWS::Resources::RW_IOSYSTEM_SIGNALS; @@ -142,7 +143,7 @@ RWSClient::RWSResult RWSClient::getIOSignals() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getIOSignal(const std::string& iosignal) +RWSResult RWSClient::getIOSignal(const std::string& iosignal) { std::string uri = generateIOSignalPath(iosignal); @@ -153,7 +154,7 @@ RWSClient::RWSResult RWSClient::getIOSignal(const std::string& iosignal) return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getMechanicalUnitStaticInfo(const std::string& mechunit) +RWSResult RWSClient::getMechanicalUnitStaticInfo(const std::string& mechunit) { std::string uri = generateMechanicalUnitPath(mechunit) + "?resource=static"; @@ -164,7 +165,7 @@ RWSClient::RWSResult RWSClient::getMechanicalUnitStaticInfo(const std::string& m return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getMechanicalUnitDynamicInfo(const std::string& mechunit) +RWSResult RWSClient::getMechanicalUnitDynamicInfo(const std::string& mechunit) { std::string uri = generateMechanicalUnitPath(mechunit) + "?resource=dynamic"; @@ -175,7 +176,7 @@ RWSClient::RWSResult RWSClient::getMechanicalUnitDynamicInfo(const std::string& return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getMechanicalUnitJointTarget(const std::string& mechunit) +RWSResult RWSClient::getMechanicalUnitJointTarget(const std::string& mechunit) { std::string uri = generateMechanicalUnitPath(mechunit) + Resources::JOINTTARGET; @@ -186,7 +187,7 @@ RWSClient::RWSResult RWSClient::getMechanicalUnitJointTarget(const std::string& return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getMechanicalUnitRobTarget(const std::string& mechunit, +RWSResult RWSClient::getMechanicalUnitRobTarget(const std::string& mechunit, const Coordinate& coordinate, const std::string& tool, const std::string& wobj) @@ -206,16 +207,16 @@ RWSClient::RWSResult RWSClient::getMechanicalUnitRobTarget(const std::string& me const std::string coordinate_arg = "?coordinate="; switch (coordinate) { - case BASE: + case Coordinate::BASE: uri += coordinate_arg + SystemConstants::General::COORDINATE_BASE + args; break; - case WORLD: + case Coordinate::WORLD: uri += coordinate_arg + SystemConstants::General::COORDINATE_WORLD + args; break; - case TOOL: + case Coordinate::TOOL: uri += coordinate_arg + SystemConstants::General::COORDINATE_TOOL + args; break; - case WOBJ: + case Coordinate::WOBJ: uri += coordinate_arg + SystemConstants::General::COORDINATE_WOBJ + args; break; default: @@ -231,7 +232,7 @@ RWSClient::RWSResult RWSClient::getMechanicalUnitRobTarget(const std::string& me return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getRAPIDExecution() +RWSResult RWSClient::getRAPIDExecution() { std::string uri = Resources::RW_RAPID_EXECUTION; @@ -242,7 +243,7 @@ RWSClient::RWSResult RWSClient::getRAPIDExecution() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getRAPIDModulesInfo(const std::string& task) +RWSResult RWSClient::getRAPIDModulesInfo(const std::string& task) { std::string uri = Resources::RW_RAPID_MODULES + "?" + Queries::TASK + task; @@ -253,7 +254,7 @@ RWSClient::RWSResult RWSClient::getRAPIDModulesInfo(const std::string& task) return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getRAPIDTasks() +RWSResult RWSClient::getRAPIDTasks() { std::string uri = Resources::RW_RAPID_TASKS; @@ -264,7 +265,7 @@ RWSClient::RWSResult RWSClient::getRAPIDTasks() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getRobotWareSystem() +RWSResult RWSClient::getRobotWareSystem() { std::string uri = Resources::RW_SYSTEM; @@ -275,7 +276,7 @@ RWSClient::RWSResult RWSClient::getRobotWareSystem() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getSpeedRatio() +RWSResult RWSClient::getSpeedRatio() { std::string uri = "/rw/panel/speedratio"; @@ -286,7 +287,7 @@ RWSClient::RWSResult RWSClient::getSpeedRatio() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getPanelControllerState() +RWSResult RWSClient::getPanelControllerState() { std::string uri = Resources::RW_PANEL_CTRLSTATE; @@ -297,7 +298,7 @@ RWSClient::RWSResult RWSClient::getPanelControllerState() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getPanelOperationMode() +RWSResult RWSClient::getPanelOperationMode() { std::string uri = Resources::RW_PANEL_OPMODE; @@ -308,7 +309,7 @@ RWSClient::RWSResult RWSClient::getPanelOperationMode() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource) +RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource) { std::string uri = generateRAPIDDataPath(resource); @@ -319,7 +320,7 @@ RWSClient::RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource, RAPIDSymbolDataAbstract* p_data) +RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource, RAPIDSymbolDataAbstract* p_data) { RWSResult result; std::string data_type; @@ -357,7 +358,7 @@ RWSClient::RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource return result; } -RWSClient::RWSResult RWSClient::getRAPIDSymbolProperties(const RAPIDResource& resource) +RWSResult RWSClient::getRAPIDSymbolProperties(const RAPIDResource& resource) { std::string uri = generateRAPIDPropertiesPath(resource); @@ -368,7 +369,7 @@ RWSClient::RWSResult RWSClient::getRAPIDSymbolProperties(const RAPIDResource& re return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::setIOSignal(const std::string& iosignal, const std::string& value) +RWSResult RWSClient::setIOSignal(const std::string& iosignal, const std::string& value) { std::string uri = generateIOSignalPath(iosignal) + "?" + Queries::ACTION_SET; std::string content = Identifiers::LVALUE + "=" + value; @@ -380,7 +381,7 @@ RWSClient::RWSResult RWSClient::setIOSignal(const std::string& iosignal, const s return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const std::string& data) +RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const std::string& data) { std::string uri = generateRAPIDDataPath(resource) + "?" + Queries::ACTION_SET; std::string content = Identifiers::VALUE + "=" + data; @@ -392,12 +393,12 @@ RWSClient::RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const RAPIDSymbolDataAbstract& data) +RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const RAPIDSymbolDataAbstract& data) { return setRAPIDSymbolData(resource, data.constructString()); } -RWSClient::RWSResult RWSClient::startRAPIDExecution() +RWSResult RWSClient::startRAPIDExecution() { std::string uri = Resources::RW_RAPID_EXECUTION + "?" + Queries::ACTION_START; std::string content = "regain=continue&execmode=continue&cycle=forever&condition=none&stopatbp=disabled&alltaskbytsp=false"; @@ -409,7 +410,7 @@ RWSClient::RWSResult RWSClient::startRAPIDExecution() return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::stopRAPIDExecution() +RWSResult RWSClient::stopRAPIDExecution() { std::string uri = Resources::RW_RAPID_EXECUTION + "?" + Queries::ACTION_STOP; std::string content = "stopmode=stop"; @@ -421,7 +422,7 @@ RWSClient::RWSResult RWSClient::stopRAPIDExecution() return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::resetRAPIDProgramPointer() +RWSResult RWSClient::resetRAPIDProgramPointer() { std::string uri = Resources::RW_RAPID_EXECUTION + "?" + Queries::ACTION_RESETPP; @@ -432,7 +433,7 @@ RWSClient::RWSResult RWSClient::resetRAPIDProgramPointer() return evaluatePOCOResult(httpPost(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::setMotorsOn() +RWSResult RWSClient::setMotorsOn() { std::string uri = Resources::RW_PANEL_CTRLSTATE + "?" + Queries::ACTION_SETCTRLSTATE; std::string content = "ctrl-state=motoron"; @@ -444,7 +445,7 @@ RWSClient::RWSResult RWSClient::setMotorsOn() return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::setMotorsOff() +RWSResult RWSClient::setMotorsOff() { std::string uri = Resources::RW_PANEL_CTRLSTATE + "?" + Queries::ACTION_SETCTRLSTATE; std::string content = "ctrl-state=motoroff"; @@ -456,7 +457,7 @@ RWSClient::RWSResult RWSClient::setMotorsOff() return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::setSpeedRatio(unsigned int ratio) +RWSResult RWSClient::setSpeedRatio(unsigned int ratio) { if(ratio > 100) throw std::out_of_range("Speed ratio argument out of range (should be 0 <= ratio <= 100)"); @@ -474,7 +475,7 @@ RWSClient::RWSResult RWSClient::setSpeedRatio(unsigned int ratio) return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::getFile(const FileResource& resource, std::string* p_file_content) +RWSResult RWSClient::getFile(const FileResource& resource, std::string* p_file_content) { RWSResult rws_result; POCOClient::POCOResult poco_result; @@ -499,7 +500,7 @@ RWSClient::RWSResult RWSClient::getFile(const FileResource& resource, std::strin return rws_result; } -RWSClient::RWSResult RWSClient::uploadFile(const FileResource& resource, const std::string& file_content) +RWSResult RWSClient::uploadFile(const FileResource& resource, const std::string& file_content) { std::string uri = generateFilePath(resource); std::string content = file_content; @@ -512,7 +513,7 @@ RWSClient::RWSResult RWSClient::uploadFile(const FileResource& resource, const s return evaluatePOCOResult(httpPut(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::deleteFile(const FileResource& resource) +RWSResult RWSClient::deleteFile(const FileResource& resource) { std::string uri = generateFilePath(resource); @@ -524,13 +525,13 @@ RWSClient::RWSResult RWSClient::deleteFile(const FileResource& resource) return evaluatePOCOResult(httpDelete(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::startSubscription(const SubscriptionResources& resources) +RWSResult RWSClient::startSubscription(const SubscriptionResources& resources) { RWSResult result; if (!webSocketExist()) { - std::vector temp = resources.getResources(); + std::vector temp = resources.getResources(); // Generate content for a subscription HTTP post request. std::stringstream subscription_content; @@ -574,7 +575,7 @@ RWSClient::RWSResult RWSClient::startSubscription(const SubscriptionResources& r return result; } -RWSClient::RWSResult RWSClient::waitForSubscriptionEvent() +RWSResult RWSClient::waitForSubscriptionEvent() { EvaluationConditions evaluation_conditions; evaluation_conditions.parse_message_into_xml = true; @@ -583,7 +584,7 @@ RWSClient::RWSResult RWSClient::waitForSubscriptionEvent() return evaluatePOCOResult(webSocketReceiveFrame(), evaluation_conditions); } -RWSClient::RWSResult RWSClient::endSubscription() +RWSResult RWSClient::endSubscription() { RWSResult result; @@ -609,7 +610,7 @@ void RWSClient::forceCloseSubscription() webSocketShutdown(); } -RWSClient::RWSResult RWSClient::logout() +RWSResult RWSClient::logout() { std::string uri = Resources::LOGOUT; @@ -620,7 +621,7 @@ RWSClient::RWSResult RWSClient::logout() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSClient::RWSResult RWSClient::registerLocalUser(const std::string& username, +RWSResult RWSClient::registerLocalUser(const std::string& username, const std::string& application, const std::string& location) { @@ -640,7 +641,7 @@ RWSClient::RWSResult RWSClient::registerLocalUser(const std::string& username, return result; } -RWSClient::RWSResult RWSClient::registerRemoteUser(const std::string& username, +RWSResult RWSClient::registerRemoteUser(const std::string& username, const std::string& application, const std::string& location) { @@ -664,7 +665,7 @@ RWSClient::RWSResult RWSClient::registerRemoteUser(const std::string& username, * Auxiliary methods */ -RWSClient::RWSResult RWSClient::evaluatePOCOResult(const POCOResult& poco_result, +RWSResult RWSClient::evaluatePOCOResult(const POCOResult& poco_result, const EvaluationConditions& conditions) { RWSResult result; @@ -744,7 +745,7 @@ void RWSClient::parseMessage(RWSResult* result, const POCOResult& poco_result) } } -std::string RWSClient::getLogText(const bool verbose) +std::string RWSClient::getLogText(const bool verbose) const { if (log_.size() == 0) { @@ -763,7 +764,7 @@ std::string RWSClient::getLogText(const bool verbose) return ss.str(); } -std::string RWSClient::getLogTextLatestEvent(const bool verbose) +std::string RWSClient::getLogTextLatestEvent(const bool verbose) const { return (log_.size() == 0 ? "" : log_[0].toString(verbose, 0)); } diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index b964aee9..62c98b38 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -65,7 +65,7 @@ typedef SystemConstants::RWS::XMLAttributes XMLAttributes; * Primary methods */ -RWSInterface::RuntimeInfo RWSInterface::collectRuntimeInfo() +RuntimeInfo RWSInterface::collectRuntimeInfo() { RuntimeInfo runtime_info; @@ -79,7 +79,7 @@ RWSInterface::RuntimeInfo RWSInterface::collectRuntimeInfo() return runtime_info; } -RWSInterface::StaticInfo RWSInterface::collectStaticInfo() +StaticInfo RWSInterface::collectStaticInfo() { StaticInfo static_info; @@ -93,7 +93,7 @@ std::vector RWSInterface::getCFGArms() { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::ARM); + RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::ARM); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; @@ -137,7 +137,7 @@ std::vector RWSInterface::getCFGJoints() { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getConfigurationInstances("MOC", "JOINT"); + RWSResult rws_result = rws_client_.getConfigurationInstances("MOC", "JOINT"); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; @@ -191,7 +191,7 @@ std::vector RWSInterface::getCFGMechanicalUnits() { std::vector result; - RWSClient::RWSResult rws_result; + RWSResult rws_result; rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::MECHANICAL_UNIT); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); @@ -239,7 +239,7 @@ std::vector RWSInterface::getCFGMechanicalUnitGro { std::vector result; - RWSClient::RWSResult rws_result; + RWSResult rws_result; rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::MECHANICAL_UNIT_GROUP); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); @@ -287,7 +287,7 @@ std::vector RWSInterface::getCFGPresentOptions() { std::vector result; - RWSClient::RWSResult rws_result; + RWSResult rws_result; rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::PRESENT_OPTIONS); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); @@ -325,7 +325,7 @@ std::vector RWSInterface::getCFGRobots() { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::ROBOT); + RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::ROBOT); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; @@ -423,7 +423,7 @@ std::vector RWSInterface::getCFGSingles() { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::SINGLE); + RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::SINGLE); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; @@ -516,7 +516,7 @@ std::vector RWSInterface::getCFGTransmission() { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getConfigurationInstances("MOC", "TRANSMISSION"); + RWSResult rws_result = rws_client_.getConfigurationInstances("MOC", "TRANSMISSION"); if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; @@ -548,11 +548,11 @@ std::vector RWSInterface::getCFGTransmission() return result; } -std::vector RWSInterface::getPresentRobotWareOptions() +std::vector RWSInterface::getPresentRobotWareOptions() { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, + RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::PRESENT_OPTIONS); std::vector node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_IA_T_LI); @@ -573,7 +573,7 @@ std::string RWSInterface::getIOSignal(const std::string& iosignal) { std::string result; - RWSClient::RWSResult rws_result = rws_client_.getIOSignal(iosignal); + RWSResult rws_result = rws_client_.getIOSignal(iosignal); if (rws_result.success) { @@ -587,7 +587,7 @@ bool RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, Mech { bool result = false; - RWSClient::RWSResult rws_result = rws_client_.getMechanicalUnitStaticInfo(mechunit); + RWSResult rws_result = rws_client_.getMechanicalUnitStaticInfo(mechunit); if(rws_result.success) { @@ -599,23 +599,23 @@ bool RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, Mech std::string type = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "type")); // Assume mechanical unit type is undefined, update based on contents of 'type'. - static_info.type = UNDEFINED; + static_info.type = MechanicalUnitType::UNDEFINED; if(type == "None") { - static_info.type = NONE; + static_info.type = MechanicalUnitType::NONE; } else if(type == "TCPRobot") { - static_info.type = TCP_ROBOT; + static_info.type = MechanicalUnitType::TCP_ROBOT; } else if(type == "Robot") { - static_info.type = ROBOT; + static_info.type = MechanicalUnitType::ROBOT; } else if(type == "Single") { - static_info.type = SINGLE; + static_info.type = MechanicalUnitType::SINGLE; } std::stringstream axes(xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "axes"))); @@ -628,7 +628,7 @@ bool RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, Mech if(!static_info.task_name.empty() && !static_info.is_integrated_unit.empty() && !static_info.has_integrated_unit.empty() && - static_info.type != UNDEFINED && + static_info.type != MechanicalUnitType::UNDEFINED && !axes.fail() && !axes_total.fail()) { result = true; @@ -642,7 +642,7 @@ bool RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, Mec { bool result = false; - RWSClient::RWSResult rws_result = rws_client_.getMechanicalUnitDynamicInfo(mechunit); + RWSResult rws_result = rws_client_.getMechanicalUnitDynamicInfo(mechunit); if(rws_result.success) { @@ -658,31 +658,31 @@ bool RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, Mec std::string coord_system = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "coord-system")); // Assume mechanical unit mode is unknown, update based on contents of 'mode'. - dynamic_info.mode = UNKNOWN_MODE; + dynamic_info.mode = MechanicalUnitMode::UNKNOWN_MODE; if(mode == "Activated") { - dynamic_info.mode = ACTIVATED; + dynamic_info.mode = MechanicalUnitMode::ACTIVATED; } else if(mode == "Deactivated") { - dynamic_info.mode = DEACTIVATED; + dynamic_info.mode = MechanicalUnitMode::DEACTIVATED; } // Assume mechanical unit coordinate system is world, update based on contents of 'coord_system'. - dynamic_info.coord_system = RWSClient::WORLD; + dynamic_info.coord_system = Coordinate::WORLD; if(coord_system == "Base") { - dynamic_info.coord_system = RWSClient::BASE; + dynamic_info.coord_system = Coordinate::BASE; } else if(coord_system == "Tool") { - dynamic_info.coord_system = RWSClient::TOOL; + dynamic_info.coord_system = Coordinate::TOOL; } else if(coord_system == "Wobj") { - dynamic_info.coord_system = RWSClient::WOBJ; + dynamic_info.coord_system = Coordinate::WOBJ; } // Basic verification. @@ -692,7 +692,7 @@ bool RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, Mec !dynamic_info.total_payload_name.empty() && !dynamic_info.status.empty() && !dynamic_info.jog_mode.empty() && - dynamic_info.mode != UNKNOWN_MODE) + dynamic_info.mode != MechanicalUnitMode::UNKNOWN_MODE) { result = true; } @@ -707,7 +707,7 @@ bool RWSInterface::getMechanicalUnitJointTarget(const std::string& mechunit, Joi if (p_jointtarget) { - RWSClient::RWSResult rws_result = rws_client_.getMechanicalUnitJointTarget(mechunit); + RWSResult rws_result = rws_client_.getMechanicalUnitJointTarget(mechunit); result = rws_result.success; if (result) @@ -737,7 +737,7 @@ bool RWSInterface::getMechanicalUnitJointTarget(const std::string& mechunit, Joi bool RWSInterface::getMechanicalUnitRobTarget(const std::string& mechunit, RobTarget* p_robtarget, - const RWSClient::Coordinate& coordinate, + Coordinate coordinate, const std::string& tool, const std::string& wobj) { @@ -745,7 +745,7 @@ bool RWSInterface::getMechanicalUnitRobTarget(const std::string& mechunit, if (p_robtarget) { - RWSClient::RWSResult rws_result = rws_client_.getMechanicalUnitRobTarget(mechunit, coordinate, tool, wobj); + RWSResult rws_result = rws_client_.getMechanicalUnitRobTarget(mechunit, coordinate, tool, wobj); result = rws_result.success; if (result) @@ -783,7 +783,7 @@ bool RWSInterface::setRAPIDSymbolData(const std::string& task, const std::string& name, const std::string& data) { - return rws_client_.setRAPIDSymbolData(RWSClient::RAPIDResource(task, module, name), data).success; + return rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data).success; } bool RWSInterface::setRAPIDSymbolData(const std::string& task, @@ -791,14 +791,14 @@ bool RWSInterface::setRAPIDSymbolData(const std::string& task, const std::string& name, const RAPIDSymbolDataAbstract& data) { - return rws_client_.setRAPIDSymbolData(RWSClient::RAPIDResource(task, module, name), data).success; + return rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data).success; } bool RWSInterface::setRAPIDSymbolData(const std::string& task, - const RWSClient::RAPIDSymbolResource& symbol, + const RAPIDSymbolResource& symbol, const RAPIDSymbolDataAbstract& data) { - return rws_client_.setRAPIDSymbolData(RWSClient::RAPIDResource(task, symbol), data).success; + return rws_client_.setRAPIDSymbolData(RAPIDResource(task, symbol), data).success; } bool RWSInterface::startRAPIDExecution() @@ -831,11 +831,11 @@ bool RWSInterface::setSpeedRatio(unsigned int ratio) return rws_client_.setSpeedRatio(ratio).success; } -std::vector RWSInterface::getRAPIDModulesInfo(const std::string& task) +std::vector RWSInterface::getRAPIDModulesInfo(const std::string& task) { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getRAPIDModulesInfo(task); + RWSResult rws_result = rws_client_.getRAPIDModulesInfo(task); std::vector node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_RAP_MODULE_INFO_LI); @@ -850,11 +850,11 @@ std::vector RWSInterface::getRAPIDModulesInfo(con return result; } -std::vector RWSInterface::getRAPIDTasks() +std::vector RWSInterface::getRAPIDTasks() { std::vector result; - RWSClient::RWSResult rws_result = rws_client_.getRAPIDTasks(); + RWSResult rws_result = rws_client_.getRAPIDTasks(); std::vector node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_RAP_TASK_LI); for (size_t i = 0; i < node_list.size(); ++i) @@ -865,23 +865,23 @@ std::vector RWSInterface::getRAPIDTasks() std::string temp = xmlFindTextContent(node_list.at(i), XMLAttributes::CLASS_EXCSTATE); // Assume task state is unknown, update based on contents of 'temp'. - RAPIDTaskExecutionState execution_state = UNKNOWN; + RAPIDTaskExecutionState execution_state = RAPIDTaskExecutionState::UNKNOWN; if(temp == "read") { - execution_state = READY; + execution_state = RAPIDTaskExecutionState::READY; } else if(temp == "stop") { - execution_state = STOPPED; + execution_state = RAPIDTaskExecutionState::STOPPED; } else if(temp == "star") { - execution_state = STARTED; + execution_state = RAPIDTaskExecutionState::STARTED; } else if(temp == "unin") { - execution_state = UNINITIALIZED; + execution_state = RAPIDTaskExecutionState::UNINITIALIZED; } result.push_back(RAPIDTaskInfo(name, is_motion_task, is_active, execution_state)); @@ -894,7 +894,7 @@ unsigned int RWSInterface::getSpeedRatio() { unsigned int speed_ratio = 0; - RWSClient::RWSResult rws_result = rws_client_.getSpeedRatio(); + RWSResult rws_result = rws_client_.getSpeedRatio(); if(!rws_result.success) throw std::runtime_error("Failed to get the speed ratio"); std::stringstream ss(xmlFindTextContent(rws_result.p_xml_document, XMLAttribute(Identifiers::CLASS, "speedratio"))); @@ -904,11 +904,11 @@ unsigned int RWSInterface::getSpeedRatio() return speed_ratio; } -RWSInterface::SystemInfo RWSInterface::getSystemInfo() +SystemInfo RWSInterface::getSystemInfo() { SystemInfo result; - RWSClient::RWSResult rws_result = rws_client_.getRobotWareSystem(); + RWSResult rws_result = rws_client_.getRobotWareSystem(); std::vector node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_SYS_SYSTEM_LI); for (size_t i = 0; i < node_list.size(); ++i) @@ -959,7 +959,7 @@ std::string RWSInterface::getRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name) { - return xmlFindTextContent(rws_client_.getRAPIDSymbolData(RWSClient::RAPIDResource(task, module, name)).p_xml_document, + return xmlFindTextContent(rws_client_.getRAPIDSymbolData(RAPIDResource(task, module, name)).p_xml_document, XMLAttributes::CLASS_VALUE); } @@ -968,39 +968,39 @@ bool RWSInterface::getRAPIDSymbolData(const std::string& task, const std::string& name, RAPIDSymbolDataAbstract* p_data) { - return rws_client_.getRAPIDSymbolData(RWSClient::RAPIDResource(task, module, name), p_data).success; + return rws_client_.getRAPIDSymbolData(RAPIDResource(task, module, name), p_data).success; } bool RWSInterface::getRAPIDSymbolData(const std::string& task, - const RWSClient::RAPIDSymbolResource& symbol, + const RAPIDSymbolResource& symbol, RAPIDSymbolDataAbstract* p_data) { - return rws_client_.getRAPIDSymbolData(RWSClient::RAPIDResource(task, symbol), p_data).success; + return rws_client_.getRAPIDSymbolData(RAPIDResource(task, symbol), p_data).success; } -bool RWSInterface::getFile(const RWSClient::FileResource& resource, std::string* p_file_content) +bool RWSInterface::getFile(const FileResource& resource, std::string* p_file_content) { return rws_client_.getFile(resource, p_file_content).success; } -bool RWSInterface::uploadFile(const RWSClient::FileResource& resource, const std::string& file_content) +bool RWSInterface::uploadFile(const FileResource& resource, const std::string& file_content) { return rws_client_.uploadFile(resource, file_content).success; } -bool RWSInterface::deleteFile(const RWSClient::FileResource& resource) +bool RWSInterface::deleteFile(const FileResource& resource) { return rws_client_.deleteFile(resource).success; } -bool RWSInterface::startSubscription (const RWSClient::SubscriptionResources& resources) +bool RWSInterface::startSubscription (const SubscriptionResources& resources) { return rws_client_.startSubscription(resources).success; } bool RWSInterface::waitForSubscriptionEvent() { - RWSClient::RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); + RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); return (rws_result.success && !rws_result.p_xml_document.isNull()); } @@ -1011,7 +1011,7 @@ bool RWSInterface::waitForSubscriptionEvent(Poco::AutoPtr* if (p_xml_document) { - RWSClient::RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); + RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); if (rws_result.success && !rws_result.p_xml_document.isNull()) { @@ -1061,7 +1061,7 @@ std::string RWSInterface::getLogTextLatestEvent(const bool verbose) * Auxiliary methods */ -TriBool RWSInterface::compareSingleContent(const RWSClient::RWSResult& rws_result, +TriBool RWSInterface::compareSingleContent(const RWSResult& rws_result, const XMLAttribute& attribute, const std::string& compare_string) { diff --git a/src/rws_state_machine_interface.cpp b/src/rws_state_machine_interface.cpp index 7be51f05..96e6996d 100644 --- a/src/rws_state_machine_interface.cpp +++ b/src/rws_state_machine_interface.cpp @@ -44,7 +44,6 @@ namespace rws * Struct definitions: RWSStateMachineInterface::ResourceIdentifiers */ -typedef RWSClient::RAPIDSymbolResource RAPIDSymbolResource; typedef RWSStateMachineInterface::States States; typedef RWSStateMachineInterface::EGMActions EGMActions; typedef RWSStateMachineInterface::ResourceIdentifiers::RAPID::Symbols Symbols; From 11e376f04669446b9512091087f0dcc773888977 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sat, 26 Dec 2020 00:04:30 +0100 Subject: [PATCH 04/17] Pulling out nested classes. --- include/abb_librws/subscription.h | 92 +++++++++++++++++++++++++++++++ 1 file changed, 92 insertions(+) create mode 100644 include/abb_librws/subscription.h diff --git a/include/abb_librws/subscription.h b/include/abb_librws/subscription.h new file mode 100644 index 00000000..e2589d3e --- /dev/null +++ b/include/abb_librws/subscription.h @@ -0,0 +1,92 @@ +#pragma once + +#include "resource.h" + +#include + + +namespace abb :: rws +{ + /** + * \brief An enum for specifying subscription priority. + */ + enum SubscriptionPriority + { + LOW, ///< Low priority. + MEDIUM, ///< Medium priority. + HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. + }; + + + /** + * \brief A struct for containing information about a subscription resource. + */ + struct SubscriptionResource + { + /** + * \brief URI of the resource. + */ + std::string resource_uri; + + /** + * \brief Priority of the subscription. + */ + SubscriptionPriority priority; + + /** + * \brief A constructor. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + SubscriptionResource(const std::string& resource_uri, const SubscriptionPriority priority) + : resource_uri(resource_uri) + , priority(priority) + {} + }; + + + /** + * \brief A class for representing subscription resources. + */ + class SubscriptionResources + { + public: + /** + * \brief A method to add information about a subscription resource. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + void add(const std::string& resource_uri, const SubscriptionPriority priority); + + /** + * \brief A method to add information about a IO signal subscription resource. + * + * \param iosignal for the IO signal's name. + * \param priority for the priority of the subscription. + */ + void addIOSignal(const std::string& iosignal, const SubscriptionPriority priority); + + /** + * \brief A method to add information about a RAPID persistant symbol subscription resource. + * + * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. + * \param priority for the priority of the subscription. + */ + void addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority); + + /** + * \brief A method for retrieving the contained subscription resources information. + * + * \return std::vector containing information of the subscription resources. + */ + const std::vector& getResources() const { return resources_; } + + private: + /** + * \brief A vector of subscription resources. + */ + std::vector resources_; + }; +} \ No newline at end of file From d83b47bc83448686f54d3285ea567da161ce6a08 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sat, 16 Jan 2021 15:04:59 +0100 Subject: [PATCH 05/17] Moved the Coordinate enum from the RWSClient class scope to the abb::rws namespace scope and made it an enum class. Passing Coordinate by value instead of by reference. --- include/abb_librws/subscription.h | 92 ------------------------------- 1 file changed, 92 deletions(-) delete mode 100644 include/abb_librws/subscription.h diff --git a/include/abb_librws/subscription.h b/include/abb_librws/subscription.h deleted file mode 100644 index e2589d3e..00000000 --- a/include/abb_librws/subscription.h +++ /dev/null @@ -1,92 +0,0 @@ -#pragma once - -#include "resource.h" - -#include - - -namespace abb :: rws -{ - /** - * \brief An enum for specifying subscription priority. - */ - enum SubscriptionPriority - { - LOW, ///< Low priority. - MEDIUM, ///< Medium priority. - HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. - }; - - - /** - * \brief A struct for containing information about a subscription resource. - */ - struct SubscriptionResource - { - /** - * \brief URI of the resource. - */ - std::string resource_uri; - - /** - * \brief Priority of the subscription. - */ - SubscriptionPriority priority; - - /** - * \brief A constructor. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - SubscriptionResource(const std::string& resource_uri, const SubscriptionPriority priority) - : resource_uri(resource_uri) - , priority(priority) - {} - }; - - - /** - * \brief A class for representing subscription resources. - */ - class SubscriptionResources - { - public: - /** - * \brief A method to add information about a subscription resource. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - void add(const std::string& resource_uri, const SubscriptionPriority priority); - - /** - * \brief A method to add information about a IO signal subscription resource. - * - * \param iosignal for the IO signal's name. - * \param priority for the priority of the subscription. - */ - void addIOSignal(const std::string& iosignal, const SubscriptionPriority priority); - - /** - * \brief A method to add information about a RAPID persistant symbol subscription resource. - * - * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. - * \param priority for the priority of the subscription. - */ - void addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority); - - /** - * \brief A method for retrieving the contained subscription resources information. - * - * \return std::vector containing information of the subscription resources. - */ - const std::vector& getResources() const { return resources_; } - - private: - /** - * \brief A vector of subscription resources. - */ - std::vector resources_; - }; -} \ No newline at end of file From 147540f0ff9b2c90f7b7484f7be49061e4a3221b Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sat, 16 Jan 2021 16:23:42 +0100 Subject: [PATCH 06/17] Refactoring the subscription mechanism. --- CMakeLists.txt | 1 + include/abb_librws/rws_client.h | 194 +--------------------- include/abb_librws/rws_poco_client.h | 85 +--------- include/abb_librws/rws_resource.h | 116 ++++++++++++++ include/abb_librws/rws_subscription.h | 183 +++++++++++++++++++++ src/rws_client.cpp | 42 ----- src/rws_poco_client.cpp | 189 ++-------------------- src/rws_subscription.cpp | 222 ++++++++++++++++++++++++++ 8 files changed, 543 insertions(+), 489 deletions(-) create mode 100644 include/abb_librws/rws_resource.h create mode 100644 include/abb_librws/rws_subscription.h create mode 100644 src/rws_subscription.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index f5abf195..2ca02e1a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -40,6 +40,7 @@ set( src/rws_poco_client.cpp src/rws_rapid.cpp src/rws_state_machine_interface.cpp + src/rws_subscription.cpp ) add_library(${PROJECT_NAME} ${SRC_FILES}) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index 01a8641a..cf467f74 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -46,6 +46,7 @@ #include "rws_common.h" #include "rws_rapid.h" #include "rws_poco_client.h" +#include "rws_subscription.h" namespace abb @@ -79,199 +80,6 @@ struct RWSResult }; -/** - * \brief A class for representing a RAPID symbol resource. - */ -struct RAPIDSymbolResource -{ - /** - * \brief A constructor. - * - * \param module specifying the name of the RAPID module containing the symbol. - * \param name specifying the name of the RAPID symbol. - */ - RAPIDSymbolResource(const std::string& module, const std::string& name) - : - module(module), - name(name) - {} - - /** - * \brief The RAPID module name. - */ - std::string module; - - /** - * \brief The RAPID symbol name. - */ - std::string name; -}; - - -/** - * \brief A class for representing a RAPID resource. - */ -struct RAPIDResource -{ - /** - * \brief A constructor. - * - * \param task specifying the name of the RAPID task containing the symbol. - * \param module specifying the name of the RAPID module containing the symbol. - * \param name specifying the name of the RAPID symbol. - */ - RAPIDResource(const std::string& task, const std::string& module, const std::string& name) - : - task(task), - module(module), - name(name) - {} - - /** - * \brief A constructor. - * - * \param task specifying the name of the RAPID task containing the symbol. - * \param symbol specifying the names of the RAPID module and the the symbol. - */ - RAPIDResource(const std::string& task, const RAPIDSymbolResource& symbol) - : - task(task), - module(symbol.module), - name(symbol.name) - {} - - /** - * \brief The RAPID task name. - */ - std::string task; - - /** - * \brief The RAPID module name. - */ - std::string module; - - /** - * \brief The RAPID symbol name. - */ - std::string name; -}; - - -/** - * \brief A class for representing a file resource. - */ -struct FileResource -{ - /** - * \brief A constructor. - * - * \param filename specifying the name of the file. - * \param directory specifying the directory of the file on the robot controller (set to $home by default). - */ - FileResource(const std::string& filename, - const std::string& directory = SystemConstants::RWS::Identifiers::HOME_DIRECTORY) - : - filename(filename), - directory(directory) - {} - - /** - * \brief The file's name. - */ - std::string filename; - - /** - * \brief The file's directory on the robot controller. - */ - std::string directory; -}; - - -/** - * \brief An enum for specifying subscription priority. - */ -enum SubscriptionPriority -{ - LOW, ///< Low priority. - MEDIUM, ///< Medium priority. - HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. -}; - - -/** - * \brief A struct for containing information about a subscription resource. - */ -struct SubscriptionResource -{ - /** - * \brief URI of the resource. - */ - std::string resource_uri; - - /** - * \brief Priority of the subscription. - */ - SubscriptionPriority priority; - - /** - * \brief A constructor. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - SubscriptionResource(const std::string& resource_uri, const SubscriptionPriority priority) - : - resource_uri(resource_uri), - priority(priority) - {} -}; - - -/** - * \brief A class for representing subscription resources. - */ -class SubscriptionResources -{ -public: - /** - * \brief A method to add information about a subscription resource. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - void add(const std::string& resource_uri, const SubscriptionPriority priority); - - /** - * \brief A method to add information about a IO signal subscription resource. - * - * \param iosignal for the IO signal's name. - * \param priority for the priority of the subscription. - */ - void addIOSignal(const std::string& iosignal, const SubscriptionPriority priority); - - /** - * \brief A method to add information about a RAPID persistant symbol subscription resource. - * - * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. - * \param priority for the priority of the subscription. - */ - void addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority); - - /** - * \brief A method for retrieving the contained subscription resources information. - * - * \return std::vector containing information of the subscription resources. - */ - const std::vector& getResources() const { return resources_; } - -private: - /** - * \brief A vector of subscription resources. - */ - std::vector resources_; -}; - - /** * \brief An enumeration of controller coordinate frames. */ diff --git a/include/abb_librws/rws_poco_client.h b/include/abb_librws/rws_poco_client.h index cb58fa0d..77826730 100644 --- a/include/abb_librws/rws_poco_client.h +++ b/include/abb_librws/rws_poco_client.h @@ -48,12 +48,6 @@ namespace abb { namespace rws { -/** - * \brief A class for a simple client based on POCO. - */ -class POCOClient -{ -public: /** * \brief A struct for containing the result of a communication. */ @@ -242,6 +236,13 @@ class POCOClient std::string toString(const bool verbose = false, const size_t indent = 0) const; }; + +/** + * \brief A class for a simple client based on POCO. + */ +class POCOClient +{ +public: /** * \brief A constructor. * @@ -320,44 +321,7 @@ class POCOClient http_client_session_.reset(); } - /** - * \brief A method for checking if the WebSocket exist. - * - * \return bool flag indicating if the WebSocket exist or not. - */ - bool webSocketExist() { return !p_websocket_.isNull(); } - - /** - * \brief A method for connecting a WebSocket. - * - * \param uri for the URI (path and query). - * \param protocol for the WebSocket protocol. - * \param timeout for the WebSocket communication timeout [microseconds]. - * - * \return POCOResult containing the result. - */ - POCOResult webSocketConnect(const std::string& uri, const std::string& protocol, const Poco::Int64 timeout); - - /** - * \brief A method for receiving a WebSocket frame. - * - * \return POCOResult containing the result. - */ - POCOResult webSocketReceiveFrame(); - - /** - * \brief Forcibly shut down the websocket connection. - * - * The connection is shut down immediately. - * Subsequently, the function will block until a current call to webSocketReceiveFrame() has finished, - * before cleaning up the local state. - * - * Note that since mutexes do not guarantee the order of acquisition for multiple contenders, - * it is undefined how many calls to webSocketReceiveFrame() will still attempt to use the shut down - * connection before the local state is cleaned. Those invocation will throw a runtime error. - */ - void webSocketShutdown(); - + /** * \brief A method for retrieving a substring in a string. * @@ -433,29 +397,6 @@ class POCOClient */ Poco::Mutex http_mutex_; - /** - * \brief A mutex for protecting the client's WebSocket pointer. - * - * This mutex must be held while setting or invalidating the p_websocket_ member. - * Note that the websocket_use_mutex_ must also be held while invalidating the pointer, - * since someone may be using it otherwise. - * - * If acquiring both websocket_connect_mutex_ and websocket_use_mutex_, - * the connect mutex must be acquired first. - */ - Poco::Mutex websocket_connect_mutex_; - - /** - * \brief A mutex for protecting the client's WebSocket resources. - * - * This mutex must be held while using the p_websocket_ member, - * and while invalidating the pointer. - * - * If acquiring both websocket_connect_mutex_ and websocket_use_mutex_, - * the connect mutex must be acquired first. - */ - Poco::Mutex websocket_use_mutex_; - /** * \brief A HTTP client session. */ @@ -470,16 +411,6 @@ class POCOClient * \brief A container for cookies received from a server. */ Poco::Net::NameValueCollection cookies_; - - /** - * \brief A buffer for a WebSocket. - */ - char websocket_buffer_[BUFFER_SIZE]; - - /** - * \brief A pointer to a WebSocket client. - */ - Poco::SharedPtr p_websocket_; }; } // end namespace rws diff --git a/include/abb_librws/rws_resource.h b/include/abb_librws/rws_resource.h new file mode 100644 index 00000000..1c2c61b8 --- /dev/null +++ b/include/abb_librws/rws_resource.h @@ -0,0 +1,116 @@ +#pragma once + +#include "rws_common.h" + +#include + + +namespace abb :: rws +{ + /** + * \brief A class for representing a RAPID symbol resource. + */ + struct RAPIDSymbolResource + { + /** + * \brief A constructor. + * + * \param module specifying the name of the RAPID module containing the symbol. + * \param name specifying the name of the RAPID symbol. + */ + RAPIDSymbolResource(const std::string& module, const std::string& name) + : + module(module), + name(name) + {} + + /** + * \brief The RAPID module name. + */ + std::string module; + + /** + * \brief The RAPID symbol name. + */ + std::string name; + }; + + + /** + * \brief A class for representing a RAPID resource. + */ + struct RAPIDResource + { + /** + * \brief A constructor. + * + * \param task specifying the name of the RAPID task containing the symbol. + * \param module specifying the name of the RAPID module containing the symbol. + * \param name specifying the name of the RAPID symbol. + */ + RAPIDResource(const std::string& task, const std::string& module, const std::string& name) + : + task(task), + module(module), + name(name) + {} + + /** + * \brief A constructor. + * + * \param task specifying the name of the RAPID task containing the symbol. + * \param symbol specifying the names of the RAPID module and the the symbol. + */ + RAPIDResource(const std::string& task, const RAPIDSymbolResource& symbol) + : + task(task), + module(symbol.module), + name(symbol.name) + {} + + /** + * \brief The RAPID task name. + */ + std::string task; + + /** + * \brief The RAPID module name. + */ + std::string module; + + /** + * \brief The RAPID symbol name. + */ + std::string name; + }; + + + /** + * \brief A class for representing a file resource. + */ + struct FileResource + { + /** + * \brief A constructor. + * + * \param filename specifying the name of the file. + * \param directory specifying the directory of the file on the robot controller (set to $home by default). + */ + FileResource(const std::string& filename, + const std::string& directory = SystemConstants::RWS::Identifiers::HOME_DIRECTORY) + : + filename(filename), + directory(directory) + {} + + /** + * \brief The file's name. + */ + std::string filename; + + /** + * \brief The file's directory on the robot controller. + */ + std::string directory; + }; +} \ No newline at end of file diff --git a/include/abb_librws/rws_subscription.h b/include/abb_librws/rws_subscription.h new file mode 100644 index 00000000..c30cdb09 --- /dev/null +++ b/include/abb_librws/rws_subscription.h @@ -0,0 +1,183 @@ +#pragma once + +#include "rws_resource.h" +#include "rws_poco_client.h" + +#include +#include +#include + +#include + + +namespace abb :: rws +{ + /** + * \brief An enum for specifying subscription priority. + */ + enum SubscriptionPriority + { + LOW, ///< Low priority. + MEDIUM, ///< Medium priority. + HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. + }; + + + /** + * \brief A struct for containing information about a subscription resource. + */ + struct SubscriptionResource + { + /** + * \brief URI of the resource. + */ + std::string resource_uri; + + /** + * \brief Priority of the subscription. + */ + SubscriptionPriority priority; + + /** + * \brief A constructor. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + SubscriptionResource(const std::string& resource_uri, const SubscriptionPriority priority) + : resource_uri(resource_uri) + , priority(priority) + {} + }; + + + /** + * \brief A class for representing subscription resources. + */ + class SubscriptionResources + { + public: + /** + * \brief A method to add information about a subscription resource. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + void add(const std::string& resource_uri, const SubscriptionPriority priority); + + /** + * \brief A method to add information about a IO signal subscription resource. + * + * \param iosignal for the IO signal's name. + * \param priority for the priority of the subscription. + */ + void addIOSignal(const std::string& iosignal, const SubscriptionPriority priority); + + /** + * \brief A method to add information about a RAPID persistant symbol subscription resource. + * + * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. + * \param priority for the priority of the subscription. + */ + void addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority); + + /** + * \brief A method for retrieving the contained subscription resources information. + * + * \return std::vector containing information of the subscription resources. + */ + const std::vector& getResources() const { return resources_; } + + private: + /** + * \brief A vector of subscription resources. + */ + std::vector resources_; + }; + + + class Subscription + { + public: + Subscription(); + + + /** + * \brief A method for checking if the WebSocket exist. + * + * \return bool flag indicating if the WebSocket exist or not. + */ + bool webSocketExist() { return !p_websocket_.isNull(); } + + /** + * \brief A method for connecting a WebSocket. + * + * \param uri for the URI (path and query). + * \param protocol for the WebSocket protocol. + * \param timeout for the WebSocket communication timeout [microseconds]. + * + * \return POCOResult containing the result. + */ + POCOResult webSocketConnect(const std::string& uri, const std::string& protocol, const Poco::Int64 timeout); + + /** + * \brief A method for receiving a WebSocket frame. + * + * \return POCOResult containing the result. + */ + POCOResult webSocketReceiveFrame(); + + /** + * \brief Forcibly shut down the websocket connection. + * + * The connection is shut down immediately. + * Subsequently, the function will block until a current call to webSocketReceiveFrame() has finished, + * before cleaning up the local state. + * + * Note that since mutexes do not guarantee the order of acquisition for multiple contenders, + * it is undefined how many calls to webSocketReceiveFrame() will still attempt to use the shut down + * connection before the local state is cleaned. Those invocation will throw a runtime error. + */ + void webSocketShutdown(); + + + private: + /** + * \brief A mutex for protecting the client's WebSocket pointer. + * + * This mutex must be held while setting or invalidating the p_websocket_ member. + * Note that the websocket_use_mutex_ must also be held while invalidating the pointer, + * since someone may be using it otherwise. + * + * If acquiring both websocket_connect_mutex_ and websocket_use_mutex_, + * the connect mutex must be acquired first. + */ + Poco::Mutex websocket_connect_mutex_; + + /** + * \brief A mutex for protecting the client's WebSocket resources. + * + * This mutex must be held while using the p_websocket_ member, + * and while invalidating the pointer. + * + * If acquiring both websocket_connect_mutex_ and websocket_use_mutex_, + * the connect mutex must be acquired first. + */ + Poco::Mutex websocket_use_mutex_; + + /** + * \brief Static constant for the socket's buffer size. + */ + static const size_t BUFFER_SIZE = 1024; + + /** + * \brief A buffer for a WebSocket. + */ + char websocket_buffer_[BUFFER_SIZE]; + + /** + * \brief A pointer to a WebSocket client. + */ + Poco::SharedPtr p_websocket_; + }; +} \ No newline at end of file diff --git a/src/rws_client.cpp b/src/rws_client.cpp index a4b0f38f..64ef6765 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -59,48 +59,6 @@ typedef SystemConstants::RWS::Resources Resources; typedef SystemConstants::RWS::Services Services; typedef SystemConstants::RWS::XMLAttributes XMLAttributes; -/*********************************************************************************************************************** - * Class definitions: SubscriptionResources - */ - -/************************************************************ - * Primary methods - */ - -void SubscriptionResources::addIOSignal(const std::string& iosignal, const SubscriptionPriority priority) -{ - std::string resource_uri = Resources::RW_IOSYSTEM_SIGNALS; - resource_uri += "/"; - resource_uri += iosignal; - resource_uri += ";"; - resource_uri += Identifiers::STATE; - - add(resource_uri, priority); -} - -void SubscriptionResources::addRAPIDPersistantVariable(const RAPIDResource& resource, - const SubscriptionPriority priority) -{ - std::string resource_uri = Resources::RW_RAPID_SYMBOL_DATA_RAPID; - resource_uri += "/"; - resource_uri += resource.task; - resource_uri += "/"; - resource_uri += resource.module; - resource_uri += "/"; - resource_uri += resource.name; - resource_uri += ";"; - resource_uri += Identifiers::VALUE; - - add(resource_uri, priority); -} - -void SubscriptionResources::add(const std::string& resource_uri, const SubscriptionPriority priority) -{ - resources_.push_back(SubscriptionResource(resource_uri, priority)); -} - - - /*********************************************************************************************************************** * Class definitions: RWSClient diff --git a/src/rws_poco_client.cpp b/src/rws_poco_client.cpp index 2314571f..4a5c1368 100644 --- a/src/rws_poco_client.cpp +++ b/src/rws_poco_client.cpp @@ -50,14 +50,14 @@ namespace abb namespace rws { /*********************************************************************************************************************** - * Struct definitions: POCOClient::POCOResult + * Struct definitions: POCOResult */ /************************************************************ * Primary methods */ -void POCOClient::POCOResult::addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, +void POCOResult::addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, const std::string& request_content) { poco_info.http.request.method = request.getMethod(); @@ -65,7 +65,7 @@ void POCOClient::POCOResult::addHTTPRequestInfo(const Poco::Net::HTTPRequest& re poco_info.http.request.content = request_content; } -void POCOClient::POCOResult::addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, +void POCOResult::addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, const std::string& response_content) { std::string header_info; @@ -80,7 +80,7 @@ void POCOClient::POCOResult::addHTTPResponseInfo(const Poco::Net::HTTPResponse& poco_info.http.response.content = response_content; } -void POCOClient::POCOResult::addWebSocketFrameInfo(const int flags, +void POCOResult::addWebSocketFrameInfo(const int flags, const std::string& frame_content) { poco_info.websocket.flags = flags; @@ -91,7 +91,7 @@ void POCOClient::POCOResult::addWebSocketFrameInfo(const int flags, * Auxiliary methods */ -std::string POCOClient::POCOResult::mapGeneralStatus() const +std::string POCOResult::mapGeneralStatus() const { std::string result; @@ -133,7 +133,7 @@ std::string POCOClient::POCOResult::mapGeneralStatus() const return result; } -std::string POCOClient::POCOResult::mapWebSocketOpcode() const +std::string POCOResult::mapWebSocketOpcode() const { std::string result; @@ -171,7 +171,7 @@ std::string POCOClient::POCOResult::mapWebSocketOpcode() const return result; } -std::string POCOClient::POCOResult::toString(const bool verbose, const size_t indent) const +std::string POCOResult::toString(const bool verbose, const size_t indent) const { std::stringstream ss; @@ -213,27 +213,27 @@ std::string POCOClient::POCOResult::toString(const bool verbose, const size_t in * Primary methods */ -POCOClient::POCOResult POCOClient::httpGet(const std::string& uri) +POCOResult POCOClient::httpGet(const std::string& uri) { return makeHTTPRequest(HTTPRequest::HTTP_GET, uri); } -POCOClient::POCOResult POCOClient::httpPost(const std::string& uri, const std::string& content) +POCOResult POCOClient::httpPost(const std::string& uri, const std::string& content) { return makeHTTPRequest(HTTPRequest::HTTP_POST, uri, content); } -POCOClient::POCOResult POCOClient::httpPut(const std::string& uri, const std::string& content) +POCOResult POCOClient::httpPut(const std::string& uri, const std::string& content) { return makeHTTPRequest(HTTPRequest::HTTP_PUT, uri, content); } -POCOClient::POCOResult POCOClient::httpDelete(const std::string& uri) +POCOResult POCOClient::httpDelete(const std::string& uri) { return makeHTTPRequest(HTTPRequest::HTTP_DELETE, uri); } -POCOClient::POCOResult POCOClient::makeHTTPRequest(const std::string& method, +POCOResult POCOClient::makeHTTPRequest(const std::string& method, const std::string& uri, const std::string& content) { @@ -314,171 +314,6 @@ POCOClient::POCOResult POCOClient::makeHTTPRequest(const std::string& method, return result; } -POCOClient::POCOResult POCOClient::webSocketConnect(const std::string& uri, - const std::string& protocol, - const Poco::Int64 timeout) -{ - // Lock the object's mutex. It is released when the method goes out of scope. - ScopedLock lock(http_mutex_); - - // Result of the communication. - POCOResult result; - - // The response and the request. - HTTPResponse response; - HTTPRequest request(HTTPRequest::HTTP_GET, uri, HTTPRequest::HTTP_1_1); - request.set("Sec-WebSocket-Protocol", protocol); - request.setCookies(cookies_); - - // Attempt the communication. - try - { - result.addHTTPRequestInfo(request); - - { - // We must have at least websocket_connect_mutext_. - // If a connection already exists, we must also have websocket_use_mutex_. - // If not, nobody should have the mutex anyway, so we should get it immediately. - ScopedLock connect_lock(websocket_connect_mutex_); - ScopedLock use_lock(websocket_use_mutex_); - - p_websocket_ = new WebSocket(http_client_session_, request, response); - p_websocket_->setReceiveTimeout(Poco::Timespan(timeout)); - } - - result.addHTTPResponseInfo(response); - result.status = POCOResult::OK; - } - catch (InvalidArgumentException& e) - { - result.status = POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT; - result.exception_message = e.displayText(); - } - catch (TimeoutException& e) - { - result.status = POCOResult::EXCEPTION_POCO_TIMEOUT; - result.exception_message = e.displayText(); - } - catch (WebSocketException& e) - { - result.status = POCOResult::EXCEPTION_POCO_WEBSOCKET; - result.exception_message = e.displayText(); - } - catch (NetException& e) - { - result.status = POCOResult::EXCEPTION_POCO_NET; - result.exception_message = e.displayText(); - } - - if (result.status != POCOResult::OK) - { - http_client_session_.reset(); - } - - return result; -} - -POCOClient::POCOResult POCOClient::webSocketReceiveFrame() -{ - // Lock the object's mutex. It is released when the method goes out of scope. - ScopedLock lock(websocket_use_mutex_); - - // Result of the communication. - POCOResult result; - - // Attempt the communication. - try - { - if (!p_websocket_.isNull()) - { - int flags = 0; - std::string content; - - // Wait for (non-ping) WebSocket frames. - do - { - flags = 0; - int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); - content = std::string(websocket_buffer_, number_of_bytes_received); - - // Check for ping frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) - { - // Reply with a pong frame. - p_websocket_->sendFrame(websocket_buffer_, - number_of_bytes_received, - WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); - } - } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); - - // Check for closing frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) - { - // Do not pass content of a closing frame to end user, - // according to "The WebSocket Protocol" RFC6455. - content.clear(); - - // Shutdown the WebSocket. - p_websocket_->shutdown(); - p_websocket_ = 0; - } - - result.addWebSocketFrameInfo(flags, content); - result.status = POCOResult::OK; - } - else - { - result.status = POCOResult::WEBSOCKET_NOT_ALLOCATED; - } - } - catch (InvalidArgumentException& e) - { - result.status = POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT; - result.exception_message = e.displayText(); - } - catch (TimeoutException& e) - { - result.status = POCOResult::EXCEPTION_POCO_TIMEOUT; - result.exception_message = e.displayText(); - } - catch (WebSocketException& e) - { - result.status = POCOResult::EXCEPTION_POCO_WEBSOCKET; - result.exception_message = e.displayText(); - } - catch (NetException& e) - { - result.status = POCOResult::EXCEPTION_POCO_NET; - result.exception_message = e.displayText(); - } - - if (result.status != POCOResult::OK) - { - http_client_session_.reset(); - } - - return result; -} - -void POCOClient::webSocketShutdown() -{ - // Make sure nobody is connecting while we're closing. - ScopedLock connect_lock(websocket_connect_mutex_); - - // Make sure there is actually a connection to close. - if (!webSocketExist()) - { - return; - } - - // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. - p_websocket_->shutdown(); - - // Also acquire the websocket lock before invalidating the pointer, - // or we will break running calls to webSocketReceiveFrame(). - ScopedLock use_lock(websocket_use_mutex_); - p_websocket_ = Poco::SharedPtr(); -} /************************************************************ * Auxiliary methods diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp new file mode 100644 index 00000000..97f56304 --- /dev/null +++ b/src/rws_subscription.cpp @@ -0,0 +1,222 @@ +#include + + +namespace abb :: rws +{ + using Resources = SystemConstants::RWS::Resources; + using Identifiers = SystemConstants::RWS::Identifiers; + + + /*********************************************************************************************************************** + * Class definitions: SubscriptionResources + */ + + /************************************************************ + * Primary methods + */ + + void SubscriptionResources::addIOSignal(const std::string& iosignal, const SubscriptionPriority priority) + { + std::string resource_uri = Resources::RW_IOSYSTEM_SIGNALS; + resource_uri += "/"; + resource_uri += iosignal; + resource_uri += ";"; + resource_uri += Identifiers::STATE; + + add(resource_uri, priority); + } + + void SubscriptionResources::addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority) + { + std::string resource_uri = Resources::RW_RAPID_SYMBOL_DATA_RAPID; + resource_uri += "/"; + resource_uri += resource.task; + resource_uri += "/"; + resource_uri += resource.module; + resource_uri += "/"; + resource_uri += resource.name; + resource_uri += ";"; + resource_uri += Identifiers::VALUE; + + add(resource_uri, priority); + } + + void SubscriptionResources::add(const std::string& resource_uri, const SubscriptionPriority priority) + { + resources_.push_back(SubscriptionResource(resource_uri, priority)); + } + + + Subscription::Subscription() + { + + } + + + POCOResult Subscription::webSocketConnect(const std::string& uri, + const std::string& protocol, + const Poco::Int64 timeout) + { + // Lock the object's mutex. It is released when the method goes out of scope. + ScopedLock lock(http_mutex_); + + // Result of the communication. + POCOResult result; + + // The response and the request. + HTTPResponse response; + HTTPRequest request(HTTPRequest::HTTP_GET, uri, HTTPRequest::HTTP_1_1); + request.set("Sec-WebSocket-Protocol", protocol); + request.setCookies(cookies_); + + // Attempt the communication. + try + { + result.addHTTPRequestInfo(request); + + { + // We must have at least websocket_connect_mutext_. + // If a connection already exists, we must also have websocket_use_mutex_. + // If not, nobody should have the mutex anyway, so we should get it immediately. + ScopedLock connect_lock(websocket_connect_mutex_); + ScopedLock use_lock(websocket_use_mutex_); + + p_websocket_ = new WebSocket(http_client_session_, request, response); + p_websocket_->setReceiveTimeout(Poco::Timespan(timeout)); + } + + result.addHTTPResponseInfo(response); + result.status = POCOResult::OK; + } + catch (InvalidArgumentException& e) + { + result.status = POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT; + result.exception_message = e.displayText(); + } + catch (TimeoutException& e) + { + result.status = POCOResult::EXCEPTION_POCO_TIMEOUT; + result.exception_message = e.displayText(); + } + catch (WebSocketException& e) + { + result.status = POCOResult::EXCEPTION_POCO_WEBSOCKET; + result.exception_message = e.displayText(); + } + catch (NetException& e) + { + result.status = POCOResult::EXCEPTION_POCO_NET; + result.exception_message = e.displayText(); + } + + if (result.status != POCOResult::OK) + { + http_client_session_.reset(); + } + + return result; + } + + POCOResult Subscription::webSocketReceiveFrame() + { + // Lock the object's mutex. It is released when the method goes out of scope. + ScopedLock lock(websocket_use_mutex_); + + // Result of the communication. + POCOResult result; + + // Attempt the communication. + try + { + if (!p_websocket_.isNull()) + { + int flags = 0; + std::string content; + + // Wait for (non-ping) WebSocket frames. + do + { + flags = 0; + int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); + content = std::string(websocket_buffer_, number_of_bytes_received); + + // Check for ping frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) + { + // Reply with a pong frame. + p_websocket_->sendFrame(websocket_buffer_, + number_of_bytes_received, + WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); + } + } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); + + // Check for closing frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) + { + // Do not pass content of a closing frame to end user, + // according to "The WebSocket Protocol" RFC6455. + content.clear(); + + // Shutdown the WebSocket. + p_websocket_->shutdown(); + p_websocket_ = 0; + } + + result.addWebSocketFrameInfo(flags, content); + result.status = POCOResult::OK; + } + else + { + result.status = POCOResult::WEBSOCKET_NOT_ALLOCATED; + } + } + catch (InvalidArgumentException& e) + { + result.status = POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT; + result.exception_message = e.displayText(); + } + catch (TimeoutException& e) + { + result.status = POCOResult::EXCEPTION_POCO_TIMEOUT; + result.exception_message = e.displayText(); + } + catch (WebSocketException& e) + { + result.status = POCOResult::EXCEPTION_POCO_WEBSOCKET; + result.exception_message = e.displayText(); + } + catch (NetException& e) + { + result.status = POCOResult::EXCEPTION_POCO_NET; + result.exception_message = e.displayText(); + } + + if (result.status != POCOResult::OK) + { + http_client_session_.reset(); + } + + return result; + } + + void Subscription::webSocketShutdown() + { + // Make sure nobody is connecting while we're closing. + ScopedLock connect_lock(websocket_connect_mutex_); + + // Make sure there is actually a connection to close. + if (!webSocketExist()) + { + return; + } + + // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. + p_websocket_->shutdown(); + + // Also acquire the websocket lock before invalidating the pointer, + // or we will break running calls to webSocketReceiveFrame(). + ScopedLock use_lock(websocket_use_mutex_); + p_websocket_ = Poco::SharedPtr(); + } + +} \ No newline at end of file From 2d4ac9ee25efbae77a8dffd823a2402d06bda598 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Thu, 28 Jan 2021 13:23:35 +0100 Subject: [PATCH 07/17] Continue refactoring the subscription mechanism --- CMakeLists.txt | 1 + include/abb_librws/rws_client.h | 49 +-- include/abb_librws/rws_interface.h | 44 +-- include/abb_librws/rws_poco_client.h | 438 +++++++----------------- include/abb_librws/rws_poco_result.h | 179 ++++++++++ include/abb_librws/rws_subscription.h | 388 +++++++++++---------- include/abb_librws/rws_websocket_info.h | 23 ++ src/rws_client.cpp | 91 +---- src/rws_interface.cpp | 39 +-- src/rws_poco_client.cpp | 190 ++-------- src/rws_poco_result.cpp | 166 +++++++++ src/rws_subscription.cpp | 255 +++++++------- 12 files changed, 883 insertions(+), 980 deletions(-) create mode 100644 include/abb_librws/rws_poco_result.h create mode 100644 include/abb_librws/rws_websocket_info.h create mode 100644 src/rws_poco_result.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 2ca02e1a..ed3be4f3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,6 +38,7 @@ set( src/rws_common.cpp src/rws_interface.cpp src/rws_poco_client.cpp + src/rws_poco_result.cpp src/rws_rapid.cpp src/rws_state_machine_interface.cpp src/rws_subscription.cpp diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index cf467f74..dd6c8bc9 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -46,7 +46,7 @@ #include "rws_common.h" #include "rws_rapid.h" #include "rws_poco_client.h" -#include "rws_subscription.h" +#include "rws_resource.h" namespace abb @@ -107,6 +107,9 @@ enum class Coordinate class RWSClient : public POCOClient { public: + class Subscription; + + /** * \brief A constructor. * @@ -440,44 +443,7 @@ class RWSClient : public POCOClient */ RWSResult deleteFile(const FileResource& resource); - /** - * \brief A method for starting for a subscription. - * - * \param resources specifying the resources to subscribe to. - * - * \return RWSResult containing the result. - */ - RWSResult startSubscription(const SubscriptionResources& resources); - - /** - * \brief A method for waiting for a subscription event. - * - * \return RWSResult containing the result. - */ - RWSResult waitForSubscriptionEvent(); - - /** - * \brief A method for ending a active subscription. - * - * \return RWSResult containing the result. - */ - RWSResult endSubscription(); - - /** - * \brief Force close the active subscription connection. - * - * This will cause waitForSubscriptionEvent() to return or throw. - * It does not delete the subscription from the controller. - * - * The preferred way to close the subscription is to request the robot controller to end it via - * endSubscription(). This function can be used to force the connection to close immediately in - * case the robot controller is not responding. - * - * This function blocks until an active waitForSubscriptionEvent() has finished. - * - */ - void forceCloseSubscription(); - + /** * \brief A method for logging out the currently active RWS session. * @@ -656,11 +622,6 @@ class RWSClient : public POCOClient * \brief Container for logging communication results. */ std::deque log_; - - /** - * \brief A subscription group id. - */ - std::string subscription_group_id_; }; } // end namespace rws diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index fc1dfd25..7bfabaf8 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -39,6 +39,7 @@ #include "rws_cfg.h" #include "rws_client.h" +#include "rws_subscription.h" namespace abb { @@ -801,46 +802,11 @@ class RWSInterface * * \param resources specifying the resources to subscribe to. * - * \return bool indicating if the communication was successful or not. - */ - bool startSubscription(const SubscriptionResources& resources); - - /** - * \brief A method for waiting for a subscription event (use if the event content is irrelevant). - * - * \return bool indicating if the communication was successful or not. - */ - bool waitForSubscriptionEvent(); - - /** - * \brief A method for waiting for a subscription event (use if the event content is important). - * - * \param p_xml_document for storing the data received in the subscription event. - * - * \return bool indicating if the communication was successful or not. - */ - bool waitForSubscriptionEvent(Poco::AutoPtr* p_xml_document); - - /** - * \brief A method for ending a active subscription. - * - * \return bool indicating if the communication was successful or not. - */ - bool endSubscription(); - - /** - * \brief Force close the active subscription connection. - * - * This will cause waitForSubscriptionEvent() to return or throw. - * It does not delete the subscription from the controller. - * - * The preferred way to close the subscription is to request the robot controller to end it via - * endSubscription(). This function can be used to force the connection to close immediately in - * case the robot controller is not responding. - * - * This function blocks until an active waitForSubscriptionEvent() has finished. + * \return \a RWSClient::Subscription object. + * + * \throw \a std::runtime_error if something goes wrong */ - void forceCloseSubscription(); + RWSClient::Subscription startSubscription(const SubscriptionResources& resources); /** * \brief A method for registering a user as local. diff --git a/include/abb_librws/rws_poco_client.h b/include/abb_librws/rws_poco_client.h index 77826730..0c69232e 100644 --- a/include/abb_librws/rws_poco_client.h +++ b/include/abb_librws/rws_poco_client.h @@ -37,293 +37,196 @@ #ifndef RWS_POCO_CLIENT_H #define RWS_POCO_CLIENT_H -#include "Poco/Mutex.h" -#include "Poco/Net/HTTPClientSession.h" -#include "Poco/Net/HTTPCredentials.h" -#include "Poco/Net/HTTPResponse.h" -#include "Poco/Net/WebSocket.h" -#include "Poco/SharedPtr.h" +#include + +#include +#include +#include +#include +#include + +#include namespace abb { namespace rws { /** - * \brief A struct for containing the result of a communication. + * \brief A class for a simple client based on POCO. */ - struct POCOResult + class POCOClient { + public: /** - * \brief An enum for specifying a general status. + * \brief A constructor. + * + * \param ip_address for the remote server's IP address. + * \param port for the remote server's port. + * \param username for the username to the remote server's authentication process. + * \param password for the password to the remote server's authentication process. */ - enum GeneralStatus + POCOClient(const std::string& ip_address, + const Poco::UInt16 port, + const std::string& username, + const std::string& password) + : + http_client_session_(ip_address, port), + http_credentials_(username, password) { - UNKNOWN, ///< Unknown status. - OK, ///< Ok status. - WEBSOCKET_NOT_ALLOCATED, ///< The WebSocket has not been allocated. - EXCEPTION_POCO_INVALID_ARGUMENT, ///< POCO invalid argument exception - EXCEPTION_POCO_TIMEOUT, ///< POCO timeout exception. - EXCEPTION_POCO_NET, ///< POCO net exception. - EXCEPTION_POCO_WEBSOCKET ///< POCO WebSocket exception. - }; + http_client_session_.setKeepAlive(true); + http_client_session_.setTimeout(Poco::Timespan(DEFAULT_HTTP_TIMEOUT)); + } /** - * \brief A struct for containing POCO info. + * \brief A destructor. */ - struct POCOInfo - { - /** - * \brief A struct for containing HTTP info. - */ - struct HTTPInfo - { - /** - * \brief A struct for containing HTTP request info. - */ - struct RequestInfo - { - /** - * \brief Method used for the request. - */ - std::string method; - - /** - * \brief URI used for the request. - */ - std::string uri; - - /** - * \brief Content used for the request. - */ - std::string content; - }; - - /** - * \brief A struct for containing HTTP response info. - */ - struct ResponseInfo - { - /** - * \brief Response status. - */ - Poco::Net::HTTPResponse::HTTPStatus status; - - /** - * \brief Response header info. - */ - std::string header_info; - - /** - * \brief Response content. - */ - std::string content; - - /** - * \brief A default constructor. - */ - ResponseInfo() : status(Poco::Net::HTTPResponse::HTTP_OK) {} - }; - - /** - * \brief Info about a HTTP request. - */ - RequestInfo request; - - /** - * \brief Info about a HTTP response. - */ - ResponseInfo response; - }; - - /** - * \brief A struct for containing WebSocket info. - */ - struct WebSocketInfo - { - /** - * \brief Flags from a received WebSocket frame. - */ - int flags; - - /** - * \brief Content from a received WebSocket frame. - */ - std::string frame_content; - - /** - * \brief A default constructor. - */ - WebSocketInfo() : flags(0) {}; - }; - - /** - * \brief Container for HTTP info. - */ - HTTPInfo http; - - /** - * \brief Container for WebSocket info. - */ - WebSocketInfo websocket; - }; + ~POCOClient() {} /** - * \brief Container for a general status. + * \brief A method for sending a HTTP GET request. + * + * \param uri for the URI (path and query). + * + * \return POCOResult containing the result. */ - GeneralStatus status; + POCOResult httpGet(const std::string& uri); /** - * \brief Container for an exception message (if one occurred). + * \brief A method for sending a HTTP POST request. + * + * \param uri for the URI (path and query). + * \param content for the request's content. + * + * \return POCOResult containing the result. */ - std::string exception_message; + POCOResult httpPost(const std::string& uri, const std::string& content = ""); /** - * \brief Container for POCO info. + * \brief A method for sending a HTTP PUT request. + * + * \param uri for the URI (path and query). + * \param content for the request's content. + * + * \return POCOResult containing the result. */ - POCOInfo poco_info; + POCOResult httpPut(const std::string& uri, const std::string& content = ""); /** - * \brief A default constructor. + * \brief A method for sending a HTTP DELETE request. + * + * \param uri for the URI (path and query). + * + * \return POCOResult containing the result. */ - POCOResult() : status(UNKNOWN) {}; + POCOResult httpDelete(const std::string& uri); /** - * \brief A method for adding info from a HTTP request. + * \brief A method for setting the HTTP communication timeout. * - * \param request for the HTTP request. - * \param request_content for the HTTP request's content. + * \note This method resets the internal HTTP client session, causing the + * RWS server (robot controller) to send a new cookie. The RWS + * session id is not changed. + * + * \param timeout for the HTTP communication timeout [microseconds]. */ - void addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, const std::string& request_content = ""); + void setHTTPTimeout(const Poco::Int64 timeout) + { + http_client_session_.setTimeout(Poco::Timespan(timeout)); + http_client_session_.reset(); + } + /** - * \brief A method for adding info from a HTTP response. + * \brief A method for connecting a WebSocket. * - * \param response for the HTTP response. - * \param response_content for the HTTP response's content. + * \param uri for the URI (path and query). + * \param protocol for the WebSocket protocol. + * \param timeout for the WebSocket communication timeout [microseconds]. + * + * \return Pointer to a client WebSocket. + * + * \throw \a std::runtime_error if something goes wrong */ - void addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, const std::string& response_content = ""); + std::unique_ptr webSocketConnect(const std::string& uri, const std::string& protocol, const Poco::Int64 timeout); + + private: /** - * \brief A method for adding info from a received WebSocket frame. + * \brief A method for making a HTTP request. + * + * \param method for the request's method. + * \param uri for the URI (path and query). + * \param content for the request's content. * - * \param flags for the received WebSocket frame's flags. - * \param frame_content for the received WebSocket frame's content. + * \return POCOResult containing the result. */ - void addWebSocketFrameInfo(const int flags, const std::string& frame_content); + POCOResult makeHTTPRequest(const std::string& method, + const std::string& uri = "/", + const std::string& content = ""); /** - * \brief A method to map the general status to a std::string. + * \brief A method for sending and receiving HTTP messages. * - * \return std::string containing the mapped general status. + * \param result for the result. + * \param request for the HTTP request. + * \param response for the HTTP response. + * \param request_content for the request's content. */ - std::string mapGeneralStatus() const; + void sendAndReceive(POCOResult& result, + Poco::Net::HTTPRequest& request, + Poco::Net::HTTPResponse& response, + const std::string& request_content); /** - * \brief A method to map the opcode of a received WebSocket frame. + * \brief A method for performing authentication. * - * \return std::string containing the mapped opcode. + * \param result for the result. + * \param request for the HTTP request. + * \param response for the HTTP response. + * \param request_content for the request's content. */ - std::string mapWebSocketOpcode() const; + void authenticate(POCOResult& result, + Poco::Net::HTTPRequest& request, + Poco::Net::HTTPResponse& response, + const std::string& request_content); /** - * \brief A method to construct a text representation of the result. - * - * \param verbose indicating if the log text should be verbose or not. - * \param indent for indentation. + * \brief A method for extracting and storing information from a cookie string. * - * \return std::string containing the text representation. + * \param cookie_string for the cookie string. */ - std::string toString(const bool verbose = false, const size_t indent = 0) const; - }; - + void extractAndStoreCookie(const std::string& cookie_string); -/** - * \brief A class for a simple client based on POCO. - */ -class POCOClient -{ -public: - /** - * \brief A constructor. - * - * \param ip_address for the remote server's IP address. - * \param port for the remote server's port. - * \param username for the username to the remote server's authentication process. - * \param password for the password to the remote server's authentication process. - */ - POCOClient(const std::string& ip_address, - const Poco::UInt16 port, - const std::string& username, - const std::string& password) - : - http_client_session_(ip_address, port), - http_credentials_(username, password) - { - http_client_session_.setKeepAlive(true); - http_client_session_.setTimeout(Poco::Timespan(DEFAULT_HTTP_TIMEOUT)); - } + /** + * \brief Static constant for the default HTTP communication timeout [microseconds]. + */ + static const Poco::Int64 DEFAULT_HTTP_TIMEOUT = 400e3; - /** - * \brief A destructor. - */ - ~POCOClient() {} - /** - * \brief A method for sending a HTTP GET request. - * - * \param uri for the URI (path and query). - * - * \return POCOResult containing the result. - */ - POCOResult httpGet(const std::string& uri); + /** + * \brief A mutex for protecting the clients's HTTP resources. + */ + Poco::Mutex http_mutex_; - /** - * \brief A method for sending a HTTP POST request. - * - * \param uri for the URI (path and query). - * \param content for the request's content. - * - * \return POCOResult containing the result. - */ - POCOResult httpPost(const std::string& uri, const std::string& content = ""); + /** + * \brief A HTTP client session. + */ + Poco::Net::HTTPClientSession http_client_session_; - /** - * \brief A method for sending a HTTP PUT request. - * - * \param uri for the URI (path and query). - * \param content for the request's content. - * - * \return POCOResult containing the result. - */ - POCOResult httpPut(const std::string& uri, const std::string& content = ""); + /** + * \brief HTTP credentials for the remote server's access authentication process. + */ + Poco::Net::HTTPCredentials http_credentials_; - /** - * \brief A method for sending a HTTP DELETE request. - * - * \param uri for the URI (path and query). - * - * \return POCOResult containing the result. - */ - POCOResult httpDelete(const std::string& uri); + /** + * \brief A container for cookies received from a server. + */ + Poco::Net::NameValueCollection cookies_; + }; - /** - * \brief A method for setting the HTTP communication timeout. - * - * \note This method resets the internal HTTP client session, causing the - * RWS server (robot controller) to send a new cookie. The RWS - * session id is not changed. - * - * \param timeout for the HTTP communication timeout [microseconds]. - */ - void setHTTPTimeout(const Poco::Int64 timeout) - { - http_client_session_.setTimeout(Poco::Timespan(timeout)); - http_client_session_.reset(); - } - /** - * \brief A method for retrieving a substring in a string. + * \brief A function for retrieving a substring in a string. * * \param whole_string for the string containing the substring. * \param substring_start start of the substring. @@ -334,85 +237,6 @@ class POCOClient std::string findSubstringContent(const std::string& whole_string, const std::string& substring_start, const std::string& substring_end); - -private: - /** - * \brief A method for making a HTTP request. - * - * \param method for the request's method. - * \param uri for the URI (path and query). - * \param content for the request's content. - * - * \return POCOResult containing the result. - */ - POCOResult makeHTTPRequest(const std::string& method, - const std::string& uri = "/", - const std::string& content = ""); - - /** - * \brief A method for sending and receiving HTTP messages. - * - * \param result for the result. - * \param request for the HTTP request. - * \param response for the HTTP response. - * \param request_content for the request's content. - */ - void sendAndReceive(POCOResult& result, - Poco::Net::HTTPRequest& request, - Poco::Net::HTTPResponse& response, - const std::string& request_content); - - /** - * \brief A method for performing authentication. - * - * \param result for the result. - * \param request for the HTTP request. - * \param response for the HTTP response. - * \param request_content for the request's content. - */ - void authenticate(POCOResult& result, - Poco::Net::HTTPRequest& request, - Poco::Net::HTTPResponse& response, - const std::string& request_content); - - /** - * \brief A method for extracting and storing information from a cookie string. - * - * \param cookie_string for the cookie string. - */ - void extractAndStoreCookie(const std::string& cookie_string); - - /** - * \brief Static constant for the default HTTP communication timeout [microseconds]. - */ - static const Poco::Int64 DEFAULT_HTTP_TIMEOUT = 400e3; - - /** - * \brief Static constant for the socket's buffer size. - */ - static const size_t BUFFER_SIZE = 1024; - - /** - * \brief A mutex for protecting the clients's HTTP resources. - */ - Poco::Mutex http_mutex_; - - /** - * \brief A HTTP client session. - */ - Poco::Net::HTTPClientSession http_client_session_; - - /** - * \brief HTTP credentials for the remote server's access authentication process. - */ - Poco::Net::HTTPCredentials http_credentials_; - - /** - * \brief A container for cookies received from a server. - */ - Poco::Net::NameValueCollection cookies_; -}; - } // end namespace rws } // end namespace abb diff --git a/include/abb_librws/rws_poco_result.h b/include/abb_librws/rws_poco_result.h new file mode 100644 index 00000000..89ab0b8c --- /dev/null +++ b/include/abb_librws/rws_poco_result.h @@ -0,0 +1,179 @@ +#pragma once + +#include + +#include +#include + +#include + + +namespace abb :: rws +{ + /** + * \brief A struct for containing the result of a communication. + */ + struct POCOResult + { + /** + * \brief An enum for specifying a general status. + */ + enum GeneralStatus + { + UNKNOWN, ///< Unknown status. + OK, ///< Ok status. + WEBSOCKET_NOT_ALLOCATED, ///< The WebSocket has not been allocated. + EXCEPTION_POCO_INVALID_ARGUMENT, ///< POCO invalid argument exception + EXCEPTION_POCO_TIMEOUT, ///< POCO timeout exception. + EXCEPTION_POCO_NET, ///< POCO net exception. + EXCEPTION_POCO_WEBSOCKET ///< POCO WebSocket exception. + }; + + /** + * \brief A struct for containing POCO info. + */ + struct POCOInfo + { + /** + * \brief A struct for containing HTTP info. + */ + struct HTTPInfo + { + /** + * \brief A struct for containing HTTP request info. + */ + struct RequestInfo + { + /** + * \brief Method used for the request. + */ + std::string method; + + /** + * \brief URI used for the request. + */ + std::string uri; + + /** + * \brief Content used for the request. + */ + std::string content; + }; + + /** + * \brief A struct for containing HTTP response info. + */ + struct ResponseInfo + { + /** + * \brief Response status. + */ + Poco::Net::HTTPResponse::HTTPStatus status; + + /** + * \brief Response header info. + */ + std::string header_info; + + /** + * \brief Response content. + */ + std::string content; + + /** + * \brief A default constructor. + */ + ResponseInfo() : status(Poco::Net::HTTPResponse::HTTP_OK) {} + }; + + /** + * \brief Info about a HTTP request. + */ + RequestInfo request; + + /** + * \brief Info about a HTTP response. + */ + ResponseInfo response; + }; + + /** + * \brief Container for HTTP info. + */ + HTTPInfo http; + + /** + * \brief Container for WebSocket info. + */ + WebSocketInfo websocket; + }; + + /** + * \brief Container for a general status. + */ + GeneralStatus status; + + /** + * \brief Container for an exception message (if one occurred). + */ + std::string exception_message; + + /** + * \brief Container for POCO info. + */ + POCOInfo poco_info; + + /** + * \brief A default constructor. + */ + POCOResult() : status(UNKNOWN) {}; + + /** + * \brief A method for adding info from a HTTP request. + * + * \param request for the HTTP request. + * \param request_content for the HTTP request's content. + */ + void addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, const std::string& request_content = ""); + + /** + * \brief A method for adding info from a HTTP response. + * + * \param response for the HTTP response. + * \param response_content for the HTTP response's content. + */ + void addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, const std::string& response_content = ""); + + /** + * \brief A method for adding info from a received WebSocket frame. + * + * \param flags for the received WebSocket frame's flags. + * \param frame_content for the received WebSocket frame's content. + */ + void addWebSocketFrameInfo(const int flags, const std::string& frame_content); + + /** + * \brief A method to map the general status to a std::string. + * + * \return std::string containing the mapped general status. + */ + std::string mapGeneralStatus() const; + + /** + * \brief A method to map the opcode of a received WebSocket frame. + * + * \return std::string containing the mapped opcode. + */ + std::string mapWebSocketOpcode() const; + + /** + * \brief A method to construct a text representation of the result. + * + * \param verbose indicating if the log text should be verbose or not. + * \param indent for indentation. + * + * \return std::string containing the text representation. + */ + std::string toString(const bool verbose = false, const size_t indent = 0) const; + }; +} \ No newline at end of file diff --git a/include/abb_librws/rws_subscription.h b/include/abb_librws/rws_subscription.h index c30cdb09..dc8c66ea 100644 --- a/include/abb_librws/rws_subscription.h +++ b/include/abb_librws/rws_subscription.h @@ -1,183 +1,227 @@ #pragma once #include "rws_resource.h" -#include "rws_poco_client.h" - -#include -#include -#include +#include "rws_client.h" #include +#include namespace abb :: rws { + /** + * \brief An enum for specifying subscription priority. + */ + enum class SubscriptionPriority + { + LOW, ///< Low priority. + MEDIUM, ///< Medium priority. + HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. + }; + + + /** + * \brief A struct for containing information about a subscription resource. + */ + struct SubscriptionResource + { + /** + * \brief URI of the resource. + */ + std::string resource_uri; + + /** + * \brief Priority of the subscription. + */ + SubscriptionPriority priority; + + /** + * \brief A constructor. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + SubscriptionResource(const std::string& resource_uri, const SubscriptionPriority priority) + : + resource_uri(resource_uri), + priority(priority) + {} + }; + + + /** + * \brief A class for representing subscription resources. + */ + class SubscriptionResources + { + public: + /** + * \brief A method to add information about a subscription resource. + * + * \param resource_uri for the URI of the resource. + * \param priority for the priority of the subscription. + */ + void add(const std::string& resource_uri, const SubscriptionPriority priority); + + /** + * \brief A method to add information about a IO signal subscription resource. + * + * \param iosignal for the IO signal's name. + * \param priority for the priority of the subscription. + */ + void addIOSignal(const std::string& iosignal, const SubscriptionPriority priority); + + /** + * \brief A method to add information about a RAPID persistant symbol subscription resource. + * + * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. + * \param priority for the priority of the subscription. + */ + void addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority); + + /** + * \brief A method for retrieving the contained subscription resources information. + * + * \return std::vector containing information of the subscription resources. + */ + const std::vector& getResources() const { return resources_; } + + private: + /** + * \brief A vector of subscription resources. + */ + std::vector resources_; + }; + + + struct SubscriptionEvent + { + std::string resourceUri; + std::string value; + }; + + + std::ostream& operator<<(std::ostream& os, SubscriptionEvent const& event); + + + /** + * \brief Manages RWS event subscription. + */ + class RWSClient::Subscription + { + public: + using WebSocket = Poco::Net::WebSocket; + + + /** + * \brief A constructor. + * + * \param client a client to subscribe + * \param resources list of resources to subscribe + */ + Subscription(RWSClient& client, SubscriptionResources const& resources); + + /** - * \brief An enum for specifying subscription priority. - */ - enum SubscriptionPriority - { - LOW, ///< Low priority. - MEDIUM, ///< Medium priority. - HIGH ///< High priority. Only RobotWare 6.05 (or newer) and for IO signals and persistant RAPID variables. - }; - - - /** - * \brief A struct for containing information about a subscription resource. - */ - struct SubscriptionResource - { - /** - * \brief URI of the resource. - */ - std::string resource_uri; - - /** - * \brief Priority of the subscription. - */ - SubscriptionPriority priority; - - /** - * \brief A constructor. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - SubscriptionResource(const std::string& resource_uri, const SubscriptionPriority priority) - : resource_uri(resource_uri) - , priority(priority) - {} - }; - - - /** - * \brief A class for representing subscription resources. - */ - class SubscriptionResources - { - public: - /** - * \brief A method to add information about a subscription resource. - * - * \param resource_uri for the URI of the resource. - * \param priority for the priority of the subscription. - */ - void add(const std::string& resource_uri, const SubscriptionPriority priority); - - /** - * \brief A method to add information about a IO signal subscription resource. - * - * \param iosignal for the IO signal's name. - * \param priority for the priority of the subscription. - */ - void addIOSignal(const std::string& iosignal, const SubscriptionPriority priority); - - /** - * \brief A method to add information about a RAPID persistant symbol subscription resource. - * - * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. - * \param priority for the priority of the subscription. - */ - void addRAPIDPersistantVariable(const RAPIDResource& resource, const SubscriptionPriority priority); - - /** - * \brief A method for retrieving the contained subscription resources information. - * - * \return std::vector containing information of the subscription resources. - */ - const std::vector& getResources() const { return resources_; } - - private: - /** - * \brief A vector of subscription resources. - */ - std::vector resources_; - }; - - - class Subscription - { - public: - Subscription(); - - - /** - * \brief A method for checking if the WebSocket exist. - * - * \return bool flag indicating if the WebSocket exist or not. - */ - bool webSocketExist() { return !p_websocket_.isNull(); } - - /** - * \brief A method for connecting a WebSocket. - * - * \param uri for the URI (path and query). - * \param protocol for the WebSocket protocol. - * \param timeout for the WebSocket communication timeout [microseconds]. - * - * \return POCOResult containing the result. - */ - POCOResult webSocketConnect(const std::string& uri, const std::string& protocol, const Poco::Int64 timeout); - - /** - * \brief A method for receiving a WebSocket frame. - * - * \return POCOResult containing the result. - */ - POCOResult webSocketReceiveFrame(); - - /** - * \brief Forcibly shut down the websocket connection. - * - * The connection is shut down immediately. - * Subsequently, the function will block until a current call to webSocketReceiveFrame() has finished, - * before cleaning up the local state. - * - * Note that since mutexes do not guarantee the order of acquisition for multiple contenders, - * it is undefined how many calls to webSocketReceiveFrame() will still attempt to use the shut down - * connection before the local state is cleaned. Those invocation will throw a runtime error. - */ - void webSocketShutdown(); - - - private: - /** - * \brief A mutex for protecting the client's WebSocket pointer. - * - * This mutex must be held while setting or invalidating the p_websocket_ member. - * Note that the websocket_use_mutex_ must also be held while invalidating the pointer, - * since someone may be using it otherwise. - * - * If acquiring both websocket_connect_mutex_ and websocket_use_mutex_, - * the connect mutex must be acquired first. - */ - Poco::Mutex websocket_connect_mutex_; - - /** - * \brief A mutex for protecting the client's WebSocket resources. - * - * This mutex must be held while using the p_websocket_ member, - * and while invalidating the pointer. - * - * If acquiring both websocket_connect_mutex_ and websocket_use_mutex_, - * the connect mutex must be acquired first. - */ - Poco::Mutex websocket_use_mutex_; - - /** - * \brief Static constant for the socket's buffer size. - */ - static const size_t BUFFER_SIZE = 1024; - - /** - * \brief A buffer for a WebSocket. - */ - char websocket_buffer_[BUFFER_SIZE]; - - /** - * \brief A pointer to a WebSocket client. - */ - Poco::SharedPtr p_websocket_; - }; + * \brief Move constructor. + * + * \a Subscription objects are moveable. + */ + Subscription(Subscription&&) = default; + + + /** + * \brief A destructor. + */ + ~Subscription(); + + + /** + * \brief A method for waiting for a subscription event. + * + * \param event event data + * + * \return true if the connection is still alive. + */ + bool waitForSubscriptionEvent(SubscriptionEvent& event); + + + /** + * \brief Force close the active subscription connection. + * + * This will cause waitForSubscriptionEvent() to return or throw. + * It does not delete the subscription from the controller. + * + * The preferred way to close the subscription is to request the robot controller to end it via + * endSubscription(). This function can be used to force the connection to close immediately in + * case the robot controller is not responding. + * + * This function blocks until an active waitForSubscriptionEvent() has finished. + * + */ + void forceCloseSubscription(); + + + private: + RWSClient& client_; + + + /** + * \brief Static constant for the socket's buffer size. + */ + static const size_t BUFFER_SIZE = 1024; + + /** + * \brief A buffer for a Subscription. + */ + char websocket_buffer_[BUFFER_SIZE]; + + /** + * \brief A pointer to a Subscription client. + */ + std::unique_ptr p_websocket_; + + /** + * \brief A subscription group id. + */ + std::string subscription_group_id_; + + + /** + * \brief Parser for XML in WebSocket frames. + */ + Poco::XML::DOMParser parser_; + + + /** + * \brief A method for receiving a WebSocket frame. + * + * \brief frame the received frame + * + * \return true if the connection is still active, false otherwise. + */ + bool webSocketReceiveFrame(WebSocketInfo& frame); + + + /** + * \brief Forcibly shut down the websocket connection. + * + * The connection is shut down immediately. + * Subsequently, the function will block until a current call to webSocketReceiveFrame() has finished, + * before cleaning up the local state. + * + * Note that since mutexes do not guarantee the order of acquisition for multiple contenders, + * it is undefined how many calls to webSocketReceiveFrame() will still attempt to use the shut down + * connection before the local state is cleaned. Those invocation will throw a runtime error. + */ + void webSocketShutdown(); + + + /** + * \brief A method for ending a active subscription. + * + * \return RWSResult containing the result. + */ + RWSResult endSubscription(); + }; } \ No newline at end of file diff --git a/include/abb_librws/rws_websocket_info.h b/include/abb_librws/rws_websocket_info.h new file mode 100644 index 00000000..e5e4688f --- /dev/null +++ b/include/abb_librws/rws_websocket_info.h @@ -0,0 +1,23 @@ +#pragma once + +#include + + +namespace abb :: rws +{ + /** + * \brief A struct for containing WebSocket info. + */ + struct WebSocketInfo + { + /** + * \brief Flags from a received WebSocket frame. + */ + int flags = 0; + + /** + * \brief Content from a received WebSocket frame. + */ + std::string frame_content; + }; +} \ No newline at end of file diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 64ef6765..210951c2 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -436,7 +436,7 @@ RWSResult RWSClient::setSpeedRatio(unsigned int ratio) RWSResult RWSClient::getFile(const FileResource& resource, std::string* p_file_content) { RWSResult rws_result; - POCOClient::POCOResult poco_result; + POCOResult poco_result; if (p_file_content) { @@ -483,90 +483,6 @@ RWSResult RWSClient::deleteFile(const FileResource& resource) return evaluatePOCOResult(httpDelete(uri), evaluation_conditions); } -RWSResult RWSClient::startSubscription(const SubscriptionResources& resources) -{ - RWSResult result; - - if (!webSocketExist()) - { - std::vector temp = resources.getResources(); - - // Generate content for a subscription HTTP post request. - std::stringstream subscription_content; - for (std::size_t i = 0; i < temp.size(); ++i) - { - subscription_content << "resources=" << i - << "&" - << i << "=" << temp.at(i).resource_uri - << "&" - << i << "-p=" << temp.at(i).priority - << (i < temp.size() - 1 ? "&" : ""); - } - - // Make a subscription request. - EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = false; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_CREATED); - POCOClient::POCOResult poco_result = httpPost(Services::SUBSCRIPTION, subscription_content.str()); - result = evaluatePOCOResult(poco_result, evaluation_conditions); - - if (result.success) - { - std::string poll = "/poll/"; - subscription_group_id_ = findSubstringContent(poco_result.poco_info.http.response.header_info, poll, "\n"); - poll += subscription_group_id_; - - // Create a WebSocket for receiving subscription events. - EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = false; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_SWITCHING_PROTOCOLS); - result = evaluatePOCOResult(webSocketConnect(poll, "robapi2_subscription", DEFAULT_SUBSCRIPTION_TIMEOUT), - evaluation_conditions); - - if (!result.success) - { - subscription_group_id_.clear(); - } - } - } - - return result; -} - -RWSResult RWSClient::waitForSubscriptionEvent() -{ - EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = true; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); - - return evaluatePOCOResult(webSocketReceiveFrame(), evaluation_conditions); -} - -RWSResult RWSClient::endSubscription() -{ - RWSResult result; - - if (webSocketExist()) - { - if (!subscription_group_id_.empty()) - { - std::string uri = Services::SUBSCRIPTION + "/" + subscription_group_id_; - - EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = false; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); - - result = evaluatePOCOResult(httpDelete(uri), evaluation_conditions); - } - } - - return result; -} - -void RWSClient::forceCloseSubscription() -{ - webSocketShutdown(); -} RWSResult RWSClient::logout() { @@ -579,6 +495,7 @@ RWSResult RWSClient::logout() return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } + RWSResult RWSClient::registerLocalUser(const std::string& username, const std::string& application, const std::string& location) @@ -703,7 +620,7 @@ void RWSClient::parseMessage(RWSResult* result, const POCOResult& poco_result) } } -std::string RWSClient::getLogText(const bool verbose) const +std::string RWSClient::getLogText(bool verbose) const { if (log_.size() == 0) { @@ -722,7 +639,7 @@ std::string RWSClient::getLogText(const bool verbose) const return ss.str(); } -std::string RWSClient::getLogTextLatestEvent(const bool verbose) const +std::string RWSClient::getLogTextLatestEvent(bool verbose) const { return (log_.size() == 0 ? "" : log_[0].toString(verbose, 0)); } diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index 62c98b38..aae914ca 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -993,44 +993,9 @@ bool RWSInterface::deleteFile(const FileResource& resource) return rws_client_.deleteFile(resource).success; } -bool RWSInterface::startSubscription (const SubscriptionResources& resources) +RWSClient::Subscription RWSInterface::startSubscription (const SubscriptionResources& resources) { - return rws_client_.startSubscription(resources).success; -} - -bool RWSInterface::waitForSubscriptionEvent() -{ - RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); - - return (rws_result.success && !rws_result.p_xml_document.isNull()); -} - -bool RWSInterface::waitForSubscriptionEvent(Poco::AutoPtr* p_xml_document) -{ - bool result = false; - - if (p_xml_document) - { - RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); - - if (rws_result.success && !rws_result.p_xml_document.isNull()) - { - *p_xml_document = rws_result.p_xml_document; - result = true; - } - } - - return result; -} - -bool RWSInterface::endSubscription() -{ - return rws_client_.endSubscription().success; -} - -void RWSInterface::forceCloseSubscription() -{ - rws_client_.webSocketShutdown(); + return RWSClient::Subscription {rws_client_, resources}; } bool RWSInterface::registerLocalUser(const std::string& username, diff --git a/src/rws_poco_client.cpp b/src/rws_poco_client.cpp index 4a5c1368..8bf25414 100644 --- a/src/rws_poco_client.cpp +++ b/src/rws_poco_client.cpp @@ -49,162 +49,6 @@ namespace abb { namespace rws { -/*********************************************************************************************************************** - * Struct definitions: POCOResult - */ - -/************************************************************ - * Primary methods - */ - -void POCOResult::addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, - const std::string& request_content) -{ - poco_info.http.request.method = request.getMethod(); - poco_info.http.request.uri = request.getURI(); - poco_info.http.request.content = request_content; -} - -void POCOResult::addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, - const std::string& response_content) -{ - std::string header_info; - - for (HTTPResponse::ConstIterator i = response.begin(); i != response.end(); ++i) - { - header_info += i->first + "=" + i->second + "\n"; - } - - poco_info.http.response.status = response.getStatus(); - poco_info.http.response.header_info = header_info; - poco_info.http.response.content = response_content; -} - -void POCOResult::addWebSocketFrameInfo(const int flags, - const std::string& frame_content) -{ - poco_info.websocket.flags = flags; - poco_info.websocket.frame_content = frame_content; -} - -/************************************************************ - * Auxiliary methods - */ - -std::string POCOResult::mapGeneralStatus() const -{ - std::string result; - - switch (status) - { - case POCOResult::UNKNOWN: - result = "UNKNOWN"; - break; - - case POCOResult::OK: - result = "OK"; - break; - - case POCOResult::WEBSOCKET_NOT_ALLOCATED: - result = "WEBSOCKET_NOT_ALLOCATED"; - break; - - case POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT: - result = "EXCEPTION_POCO_INVALID_ARGUMENT"; - break; - - case POCOResult::EXCEPTION_POCO_TIMEOUT: - result = "EXCEPTION_POCO_TIMEOUT"; - break; - - case POCOResult::EXCEPTION_POCO_NET: - result = "EXCEPTION_POCO_NET"; - break; - - case POCOResult::EXCEPTION_POCO_WEBSOCKET: - result = "EXCEPTION_POCO_WEBSOCKET"; - break; - - default: - result = "UNDEFINED"; - break; - } - - return result; -} - -std::string POCOResult::mapWebSocketOpcode() const -{ - std::string result; - - switch (poco_info.websocket.flags & WebSocket::FRAME_OP_BITMASK) - { - case WebSocket::FRAME_OP_CONT: - result = "FRAME_OP_CONT"; - break; - - case WebSocket::FRAME_OP_TEXT: - result = "FRAME_OP_TEXT"; - break; - - case WebSocket::FRAME_OP_BINARY: - result = "FRAME_OP_BINARY"; - break; - - case WebSocket::FRAME_OP_CLOSE: - result = "FRAME_OP_CLOSE"; - break; - - case WebSocket::FRAME_OP_PING: - result = "FRAME_OP_PING"; - break; - - case WebSocket::FRAME_OP_PONG: - result = "FRAME_OP_PONG"; - break; - - default: - result = "FRAME_OP_UNDEFINED"; - break; - } - - return result; -} - -std::string POCOResult::toString(const bool verbose, const size_t indent) const -{ - std::stringstream ss; - - std::string seperator = (indent == 0 ? " | " : "\n" + std::string(indent, ' ')); - - ss << "General status: " << mapGeneralStatus(); - - if (!poco_info.http.request.method.empty()) - { - ss << seperator << "HTTP Request: " << poco_info.http.request.method << " " << poco_info.http.request.uri; - - if (status == OK) - { - ss << seperator << "HTTP Response: " << poco_info.http.response.status << " - " - << HTTPResponse::getReasonForStatus(poco_info.http.response.status); - - if (verbose) - { - ss << seperator << "HTTP Response Content: " << poco_info.http.response.content; - } - } - } - else if (status == OK) - { - ss << seperator << "WebSocket frame: " << mapWebSocketOpcode(); - } - - return ss.str(); -} - - - - /*********************************************************************************************************************** * Class definitions: POCOClient */ @@ -315,6 +159,38 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, } +std::unique_ptr POCOClient::webSocketConnect(const std::string& uri, + const std::string& protocol, + const Poco::Int64 timeout) +{ + // Lock the object's mutex. It is released when the method goes out of scope. + ScopedLock lock(http_mutex_); + + // The response and the request. + HTTPResponse response; + HTTPRequest request(HTTPRequest::HTTP_GET, uri, HTTPRequest::HTTP_1_1); + request.set("Sec-WebSocket-Protocol", protocol); + request.setCookies(cookies_); + + // Attempt the communication. + try + { + std::unique_ptr websocket {new WebSocket {http_client_session_, request, response}}; + if (response.getStatus() != HTTPResponse::HTTP_SWITCHING_PROTOCOLS) + throw std::runtime_error("webSocketConnect() failed: HTTP response " + std::to_string(response.getStatus())); + + websocket->setReceiveTimeout(Poco::Timespan(timeout)); + return websocket; + } + catch (std::exception const& e) + { + // Should we really reset the session if creating the WebSocket failed? + http_client_session_.reset(); + throw; + } +} + + /************************************************************ * Auxiliary methods */ @@ -374,7 +250,7 @@ void POCOClient::extractAndStoreCookie(const std::string& cookie_string) } } -std::string POCOClient::findSubstringContent(const std::string& whole_string, +std::string findSubstringContent(const std::string& whole_string, const std::string& substring_start, const std::string& substring_end) { diff --git a/src/rws_poco_result.cpp b/src/rws_poco_result.cpp new file mode 100644 index 00000000..393ca14f --- /dev/null +++ b/src/rws_poco_result.cpp @@ -0,0 +1,166 @@ +#include + +#include + +#include + + +using namespace Poco; +using namespace Poco::Net; + + +namespace abb :: rws +{ + /*********************************************************************************************************************** + * Struct definitions: POCOResult + */ + + /************************************************************ + * Primary methods + */ + + void POCOResult::addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, + const std::string& request_content) + { + poco_info.http.request.method = request.getMethod(); + poco_info.http.request.uri = request.getURI(); + poco_info.http.request.content = request_content; + } + + void POCOResult::addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, + const std::string& response_content) + { + std::string header_info; + + for (HTTPResponse::ConstIterator i = response.begin(); i != response.end(); ++i) + { + header_info += i->first + "=" + i->second + "\n"; + } + + poco_info.http.response.status = response.getStatus(); + poco_info.http.response.header_info = header_info; + poco_info.http.response.content = response_content; + } + + void POCOResult::addWebSocketFrameInfo(const int flags, + const std::string& frame_content) + { + poco_info.websocket.flags = flags; + poco_info.websocket.frame_content = frame_content; + } + + /************************************************************ + * Auxiliary methods + */ + + std::string POCOResult::mapGeneralStatus() const + { + std::string result; + + switch (status) + { + case POCOResult::UNKNOWN: + result = "UNKNOWN"; + break; + + case POCOResult::OK: + result = "OK"; + break; + + case POCOResult::WEBSOCKET_NOT_ALLOCATED: + result = "WEBSOCKET_NOT_ALLOCATED"; + break; + + case POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT: + result = "EXCEPTION_POCO_INVALID_ARGUMENT"; + break; + + case POCOResult::EXCEPTION_POCO_TIMEOUT: + result = "EXCEPTION_POCO_TIMEOUT"; + break; + + case POCOResult::EXCEPTION_POCO_NET: + result = "EXCEPTION_POCO_NET"; + break; + + case POCOResult::EXCEPTION_POCO_WEBSOCKET: + result = "EXCEPTION_POCO_WEBSOCKET"; + break; + + default: + result = "UNDEFINED"; + break; + } + + return result; + } + + std::string POCOResult::mapWebSocketOpcode() const + { + std::string result; + + switch (poco_info.websocket.flags & WebSocket::FRAME_OP_BITMASK) + { + case WebSocket::FRAME_OP_CONT: + result = "FRAME_OP_CONT"; + break; + + case WebSocket::FRAME_OP_TEXT: + result = "FRAME_OP_TEXT"; + break; + + case WebSocket::FRAME_OP_BINARY: + result = "FRAME_OP_BINARY"; + break; + + case WebSocket::FRAME_OP_CLOSE: + result = "FRAME_OP_CLOSE"; + break; + + case WebSocket::FRAME_OP_PING: + result = "FRAME_OP_PING"; + break; + + case WebSocket::FRAME_OP_PONG: + result = "FRAME_OP_PONG"; + break; + + default: + result = "FRAME_OP_UNDEFINED"; + break; + } + + return result; + } + + std::string POCOResult::toString(const bool verbose, const size_t indent) const + { + std::stringstream ss; + + std::string seperator = (indent == 0 ? " | " : "\n" + std::string(indent, ' ')); + + ss << "General status: " << mapGeneralStatus(); + + if (!poco_info.http.request.method.empty()) + { + ss << seperator << "HTTP Request: " << poco_info.http.request.method << " " << poco_info.http.request.uri; + + if (status == OK) + { + ss << seperator << "HTTP Response: " << poco_info.http.response.status << " - " + << HTTPResponse::getReasonForStatus(poco_info.http.response.status); + + if (verbose) + { + ss << seperator << "HTTP Response Content: " << poco_info.http.response.content; + } + } + } + else if (status == OK) + { + ss << seperator << "WebSocket frame: " << mapWebSocketOpcode(); + } + + return ss.str(); + } +} \ No newline at end of file diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index 97f56304..f5607722 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -1,10 +1,16 @@ #include +#include + namespace abb :: rws { - using Resources = SystemConstants::RWS::Resources; - using Identifiers = SystemConstants::RWS::Identifiers; + using namespace Poco::Net; + + + typedef SystemConstants::RWS::Resources Resources; + typedef SystemConstants::RWS::Identifiers Identifiers; + typedef SystemConstants::RWS::Services Services; /*********************************************************************************************************************** @@ -47,176 +53,151 @@ namespace abb :: rws } - Subscription::Subscription() + RWSClient::Subscription::Subscription(RWSClient& client, SubscriptionResources const& resources) + : client_ {client} { + RWSResult result; - } + std::vector temp = resources.getResources(); + // Generate content for a subscription HTTP post request. + std::stringstream subscription_content; + for (std::size_t i = 0; i < temp.size(); ++i) + { + subscription_content << "resources=" << i + << "&" + << i << "=" << temp.at(i).resource_uri + << "&" + << i << "-p=" << static_cast(temp.at(i).priority) + << (i < temp.size() - 1 ? "&" : ""); + } - POCOResult Subscription::webSocketConnect(const std::string& uri, - const std::string& protocol, - const Poco::Int64 timeout) - { - // Lock the object's mutex. It is released when the method goes out of scope. - ScopedLock lock(http_mutex_); + // Make a subscription request. + EvaluationConditions evaluation_conditions; + evaluation_conditions.parse_message_into_xml = false; + evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_CREATED); + POCOResult poco_result = client_.httpPost(Services::SUBSCRIPTION, subscription_content.str()); + result = client_.evaluatePOCOResult(poco_result, evaluation_conditions); - // Result of the communication. - POCOResult result; + if (!result.success) + throw std::runtime_error("Unable to create RWSClient::Subscription: " + result.error_message); - // The response and the request. - HTTPResponse response; - HTTPRequest request(HTTPRequest::HTTP_GET, uri, HTTPRequest::HTTP_1_1); - request.set("Sec-WebSocket-Protocol", protocol); - request.setCookies(cookies_); + std::string poll = "/poll/"; + subscription_group_id_ = findSubstringContent(poco_result.poco_info.http.response.header_info, poll, "\n"); + poll += subscription_group_id_; - // Attempt the communication. - try - { - result.addHTTPRequestInfo(request); + p_websocket_ = client_.webSocketConnect(poll, "robapi2_subscription", DEFAULT_SUBSCRIPTION_TIMEOUT); + } - { - // We must have at least websocket_connect_mutext_. - // If a connection already exists, we must also have websocket_use_mutex_. - // If not, nobody should have the mutex anyway, so we should get it immediately. - ScopedLock connect_lock(websocket_connect_mutex_); - ScopedLock use_lock(websocket_use_mutex_); - - p_websocket_ = new WebSocket(http_client_session_, request, response); - p_websocket_->setReceiveTimeout(Poco::Timespan(timeout)); - } - result.addHTTPResponseInfo(response); - result.status = POCOResult::OK; - } - catch (InvalidArgumentException& e) - { - result.status = POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT; - result.exception_message = e.displayText(); - } - catch (TimeoutException& e) - { - result.status = POCOResult::EXCEPTION_POCO_TIMEOUT; - result.exception_message = e.displayText(); - } - catch (WebSocketException& e) + + RWSClient::Subscription::~Subscription() + { + try { - result.status = POCOResult::EXCEPTION_POCO_WEBSOCKET; - result.exception_message = e.displayText(); + // Unsubscribe from events + endSubscription(); } - catch (NetException& e) + catch (...) { - result.status = POCOResult::EXCEPTION_POCO_NET; - result.exception_message = e.displayText(); + // Catch all exceptions in dtor } + } + - if (result.status != POCOResult::OK) + bool RWSClient::Subscription::waitForSubscriptionEvent(SubscriptionEvent& event) + { + WebSocketInfo frame; + if (webSocketReceiveFrame(frame)) { - http_client_session_.reset(); - } + // std::clog << "WebSocket frame received: flags=" << frame.flags << ", frame_content=" << frame.frame_content << std::endl; + Poco::AutoPtr doc = parser_.parseString(frame.frame_content); - return result; + event.value = xmlFindTextContent(doc, XMLAttribute {"class", "lvalue"}); + if (Poco::AutoPtr node = doc->getNodeByPath("html/body/div/ul/li/a")) + event.resourceUri = xmlNodeGetAttributeValue(node, "href"); + + return true; + } + + return false; } - POCOResult Subscription::webSocketReceiveFrame() + + RWSResult RWSClient::Subscription::endSubscription() { - // Lock the object's mutex. It is released when the method goes out of scope. - ScopedLock lock(websocket_use_mutex_); + RWSResult result; - // Result of the communication. - POCOResult result; + std::string uri = Services::SUBSCRIPTION + "/" + subscription_group_id_; - // Attempt the communication. - try + EvaluationConditions evaluation_conditions; + evaluation_conditions.parse_message_into_xml = false; + evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); + + result = client_.evaluatePOCOResult(client_.httpDelete(uri), evaluation_conditions); + + return result; + } + + + bool RWSClient::Subscription::webSocketReceiveFrame(WebSocketInfo& frame) + { + // If the connection is still active... + if (p_websocket_) { - if (!p_websocket_.isNull()) + int flags = 0; + std::string content; + + // Wait for (non-ping) WebSocket frames. + do { - int flags = 0; - std::string content; + flags = 0; + int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); + content = std::string(websocket_buffer_, number_of_bytes_received); + // std::clog << "WebSocket frame received: flags=" << flags << ", content=" << content << std::endl; - // Wait for (non-ping) WebSocket frames. - do + // Check for ping frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) { - flags = 0; - int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); - content = std::string(websocket_buffer_, number_of_bytes_received); - - // Check for ping frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) - { - // Reply with a pong frame. - p_websocket_->sendFrame(websocket_buffer_, - number_of_bytes_received, - WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); - } - } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); - - // Check for closing frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) - { - // Do not pass content of a closing frame to end user, - // according to "The WebSocket Protocol" RFC6455. - content.clear(); - - // Shutdown the WebSocket. - p_websocket_->shutdown(); - p_websocket_ = 0; + // Reply with a pong frame. + p_websocket_->sendFrame(websocket_buffer_, + number_of_bytes_received, + WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); } + } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); - result.addWebSocketFrameInfo(flags, content); - result.status = POCOResult::OK; - } - else + frame.flags = flags; + frame.frame_content = content; + + // Check for closing frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) { - result.status = POCOResult::WEBSOCKET_NOT_ALLOCATED; - } - } - catch (InvalidArgumentException& e) - { - result.status = POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT; - result.exception_message = e.displayText(); - } - catch (TimeoutException& e) - { - result.status = POCOResult::EXCEPTION_POCO_TIMEOUT; - result.exception_message = e.displayText(); - } - catch (WebSocketException& e) - { - result.status = POCOResult::EXCEPTION_POCO_WEBSOCKET; - result.exception_message = e.displayText(); - } - catch (NetException& e) - { - result.status = POCOResult::EXCEPTION_POCO_NET; - result.exception_message = e.displayText(); - } + // Do not pass content of a closing frame to end user, + // according to "The WebSocket Protocol" RFC6455. + content.clear(); - if (result.status != POCOResult::OK) - { - http_client_session_.reset(); + // Shutdown the WebSocket. + p_websocket_->shutdown(); + + // Destroy the WebSocket. + } } - return result; + return (bool)p_websocket_; } - void Subscription::webSocketShutdown() - { - // Make sure nobody is connecting while we're closing. - ScopedLock connect_lock(websocket_connect_mutex_); - // Make sure there is actually a connection to close. - if (!webSocketExist()) - { - return; - } + void RWSClient::Subscription::webSocketShutdown() + { + if (p_websocket_) + // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. + p_websocket_->shutdown(); + } - // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. - p_websocket_->shutdown(); - // Also acquire the websocket lock before invalidating the pointer, - // or we will break running calls to webSocketReceiveFrame(). - ScopedLock use_lock(websocket_use_mutex_); - p_websocket_ = Poco::SharedPtr(); + std::ostream& operator<<(std::ostream& os, SubscriptionEvent const& event) + { + return os << "resourceUri=" << event.resourceUri << std::endl + << "value=" << event.value; } - } \ No newline at end of file From 546e34c2f21144ebeee4dc839238f1078a29eef8 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Fri, 29 Jan 2021 20:46:10 +0100 Subject: [PATCH 08/17] Fixed memory corruption issue --- include/abb_librws/rws_subscription.h | 16 ++++++++-------- src/rws_subscription.cpp | 26 +++++++++++++++++--------- 2 files changed, 25 insertions(+), 17 deletions(-) diff --git a/include/abb_librws/rws_subscription.h b/include/abb_librws/rws_subscription.h index dc8c66ea..82c6dae5 100644 --- a/include/abb_librws/rws_subscription.h +++ b/include/abb_librws/rws_subscription.h @@ -146,6 +146,14 @@ namespace abb :: rws bool waitForSubscriptionEvent(SubscriptionEvent& event); + /** + * \brief A method for ending a active subscription. + * + * \return RWSResult containing the result. + */ + RWSResult endSubscription(); + + /** * \brief Force close the active subscription connection. * @@ -215,13 +223,5 @@ namespace abb :: rws * connection before the local state is cleaned. Those invocation will throw a runtime error. */ void webSocketShutdown(); - - - /** - * \brief A method for ending a active subscription. - * - * \return RWSResult containing the result. - */ - RWSResult endSubscription(); }; } \ No newline at end of file diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index f5607722..5da86862 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -114,7 +114,10 @@ namespace abb :: rws Poco::AutoPtr doc = parser_.parseString(frame.frame_content); event.value = xmlFindTextContent(doc, XMLAttribute {"class", "lvalue"}); - if (Poco::AutoPtr node = doc->getNodeByPath("html/body/div/ul/li/a")) + + // IMPORTANT: don't use AutoPtr here! Otherwise you will get memory corruption: + // https://github.com/NoMagicAi/monomagic/issues/4893 + if (Poco::XML::Node const * node = doc->getNodeByPath("html/body/div/ul/li/a")) event.resourceUri = xmlNodeGetAttributeValue(node, "href"); return true; @@ -153,8 +156,10 @@ namespace abb :: rws { flags = 0; int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); + + std::clog << "RWSClient::Subscription::webSocketReceiveFrame: " << number_of_bytes_received << " bytes received\n"; content = std::string(websocket_buffer_, number_of_bytes_received); - // std::clog << "WebSocket frame received: flags=" << flags << ", content=" << content << std::endl; + std::clog << "WebSocket frame received: flags=" << flags << ", content=" << content << std::endl; // Check for ping frame. if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) @@ -166,9 +171,6 @@ namespace abb :: rws } } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); - frame.flags = flags; - frame.frame_content = content; - // Check for closing frame. if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) { @@ -176,11 +178,12 @@ namespace abb :: rws // according to "The WebSocket Protocol" RFC6455. content.clear(); - // Shutdown the WebSocket. - p_websocket_->shutdown(); - - // Destroy the WebSocket. + // Shutdown and destroy the WebSocket. + webSocketShutdown(); } + + frame.flags = flags; + frame.frame_content = content; } return (bool)p_websocket_; @@ -190,8 +193,13 @@ namespace abb :: rws void RWSClient::Subscription::webSocketShutdown() { if (p_websocket_) + { // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. p_websocket_->shutdown(); + + // Destroy the WebSocket. + p_websocket_.release(); + } } From 467a1d654bd5f582d9728938ccdf129e485bde8c Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sat, 30 Jan 2021 15:46:54 +0100 Subject: [PATCH 09/17] Added SubscriptionGroup and SubscriptionReceiver --- include/abb_librws/rws_client.h | 8 -- include/abb_librws/rws_interface.h | 4 +- include/abb_librws/rws_subscription.h | 174 +++++++++++++++++++++----- src/rws_interface.cpp | 4 +- src/rws_subscription.cpp | 91 ++++++-------- 5 files changed, 184 insertions(+), 97 deletions(-) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index dd6c8bc9..f22e3be6 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -107,9 +107,6 @@ enum class Coordinate class RWSClient : public POCOClient { public: - class Subscription; - - /** * \brief A constructor. * @@ -613,11 +610,6 @@ class RWSClient : public POCOClient */ static const size_t LOG_SIZE = 20; - /** - * \brief Static constant for the default RWS subscription timeout [microseconds]. - */ - static const Poco::Int64 DEFAULT_SUBSCRIPTION_TIMEOUT = 40e6; - /** * \brief Container for logging communication results. */ diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 7bfabaf8..d8e4183e 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -802,11 +802,11 @@ class RWSInterface * * \param resources specifying the resources to subscribe to. * - * \return \a RWSClient::Subscription object. + * \return \a Subscription object. * * \throw \a std::runtime_error if something goes wrong */ - RWSClient::Subscription startSubscription(const SubscriptionResources& resources); + Subscription startSubscription(const SubscriptionResources& resources); /** * \brief A method for registering a user as local. diff --git a/include/abb_librws/rws_subscription.h b/include/abb_librws/rws_subscription.h index 82c6dae5..b2168e9e 100644 --- a/include/abb_librws/rws_subscription.h +++ b/include/abb_librws/rws_subscription.h @@ -1,10 +1,13 @@ #pragma once #include "rws_resource.h" -#include "rws_client.h" +#include "rws_poco_client.h" + +#include #include #include +#include namespace abb :: rws @@ -94,85 +97,122 @@ namespace abb :: rws }; + /** + * \brief Contains info about a subscribed event. + */ struct SubscriptionEvent { + /** + * \brief URI of the subscribed resource + */ std::string resourceUri; + + /** + * \brief Value associated with the resource + */ std::string value; }; + /** + * \brief Outputs a \a SubscriptionEvent in a human-readable format. + */ std::ostream& operator<<(std::ostream& os, SubscriptionEvent const& event); /** - * \brief Manages RWS event subscription. + * \brief Manages an RWS subscription group. */ - class RWSClient::Subscription + class SubscriptionGroup { public: - using WebSocket = Poco::Net::WebSocket; - - /** - * \brief A constructor. + * \brief Registers a subscription at the server. * - * \param client a client to subscribe + * \param client a client to subscribe. The lifetime of the client must exceed the lifetime of the subscription group. * \param resources list of resources to subscribe */ - Subscription(RWSClient& client, SubscriptionResources const& resources); + SubscriptionGroup(POCOClient& client, SubscriptionResources const& resources); + /** + * \brief Ends an active subscription. + */ + ~SubscriptionGroup(); /** - * \brief Move constructor. + * \brief Get ID of the subscription group. * - * \a Subscription objects are moveable. + * \return ID of the subscription group. */ - Subscription(Subscription&&) = default; + std::string const& id() const noexcept + { + return subscription_group_id_; + } + private: + POCOClient& client_; /** - * \brief A destructor. + * \brief A subscription group id. */ - ~Subscription(); + std::string subscription_group_id_; + }; + /** + * \brief Receives RWS events. + */ + class SubscriptionReceiver + { + public: /** - * \brief A method for waiting for a subscription event. + * \brief Establishes WebSocket connection with the server and prepares to receive events + * for a specified subscription group. * - * \param event event data - * - * \return true if the connection is still alive. + * \param client \a POCOClient used to establish WebSocket connection. + * \param subscription_group_id ID of the subscription group to receive events for. */ - bool waitForSubscriptionEvent(SubscriptionEvent& event); + SubscriptionReceiver(POCOClient& client, std::string const& subscription_group_id); + + + /** + * \brief Closes the WebSocket connection but does not delete the subscription. + */ + ~SubscriptionReceiver(); /** - * \brief A method for ending a active subscription. + * \brief Waits for a subscription event. + * + * \param event event data * - * \return RWSResult containing the result. + * \return true if the connection is still alive, false if the connection + * has been closed by removing the subscription. */ - RWSResult endSubscription(); + bool waitForEvent(SubscriptionEvent& event); /** * \brief Force close the active subscription connection. * - * This will cause waitForSubscriptionEvent() to return or throw. + * This will cause waitForEvent() to return or throw. * It does not delete the subscription from the controller. * - * The preferred way to close the subscription is to request the robot controller to end it via - * endSubscription(). This function can be used to force the connection to close immediately in + * The preferred way to close the subscription is the destruction of the \a SubscriptionGroup object. + * This function can be used to force the connection to close immediately in * case the robot controller is not responding. * - * This function blocks until an active waitForSubscriptionEvent() has finished. + * This function blocks until an active waitForEvent() has finished. * */ - void forceCloseSubscription(); + void forceClose(); private: - RWSClient& client_; - + /** + * \brief Default RWS subscription timeout [microseconds]. + */ + static constexpr Poco::Int64 DEFAULT_SUBSCRIPTION_TIMEOUT = 40e6; /** * \brief Static constant for the socket's buffer size. @@ -185,15 +225,17 @@ namespace abb :: rws char websocket_buffer_[BUFFER_SIZE]; /** - * \brief A pointer to a Subscription client. + * \brief A mutex for protecting the client's WebSocket resources. + * + * This mutex must be held while using the p_websocket_ member, + * and while invalidating the pointer. */ - std::unique_ptr p_websocket_; + std::mutex websocket_use_mutex_; /** - * \brief A subscription group id. + * \brief A pointer to a Subscription client. */ - std::string subscription_group_id_; - + std::unique_ptr p_websocket_; /** * \brief Parser for XML in WebSocket frames. @@ -224,4 +266,68 @@ namespace abb :: rws */ void webSocketShutdown(); }; + + + /** + * \brief Manages RWS event subscription. + */ + class Subscription + { + public: + /** + * \brief A constructor. + * + * \param client a client to subscribe + * \param resources list of resources to subscribe + */ + Subscription(POCOClient& client, SubscriptionResources const& resources) + : group_ {new SubscriptionGroup {client, resources}} + , receiver_ {new SubscriptionReceiver {client, group_->id()}} + { + } + + + /** + * \brief No copy constructor. + */ + Subscription(Subscription const&) = delete; + + + /** + * \brief Ends an active subscription. + */ + ~Subscription() + { + + } + + + /** + * \brief Waits for a subscription event. + * + * \param event event data + * + * \return true if the connection is still alive, false if the connection + * has been closed by removing the subscription. + */ + bool waitForEvent(SubscriptionEvent& event) + { + return receiver_->waitForEvent(event); + } + + + /** + * \brief Ends an active subscription but does not destroy the receiver, + * s.t. if waitForEvent() is being executed in another thread it can exit gracefully. + */ + void endSubscription() + { + group_.reset(); + } + + + private: + std::unique_ptr group_; + std::unique_ptr receiver_; + }; } \ No newline at end of file diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index aae914ca..503e2f4a 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -993,9 +993,9 @@ bool RWSInterface::deleteFile(const FileResource& resource) return rws_client_.deleteFile(resource).success; } -RWSClient::Subscription RWSInterface::startSubscription (const SubscriptionResources& resources) +Subscription RWSInterface::startSubscription (const SubscriptionResources& resources) { - return RWSClient::Subscription {rws_client_, resources}; + return {rws_client_, resources}; } bool RWSInterface::registerLocalUser(const std::string& username, diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index 5da86862..5c2c65e4 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -1,6 +1,7 @@ #include #include +#include namespace abb :: rws @@ -53,11 +54,9 @@ namespace abb :: rws } - RWSClient::Subscription::Subscription(RWSClient& client, SubscriptionResources const& resources) + SubscriptionGroup::SubscriptionGroup(POCOClient& client, SubscriptionResources const& resources) : client_ {client} { - RWSResult result; - std::vector temp = resources.getResources(); // Generate content for a subscription HTTP post request. @@ -73,39 +72,35 @@ namespace abb :: rws } // Make a subscription request. - EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = false; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_CREATED); - POCOResult poco_result = client_.httpPost(Services::SUBSCRIPTION, subscription_content.str()); - result = client_.evaluatePOCOResult(poco_result, evaluation_conditions); - - if (!result.success) - throw std::runtime_error("Unable to create RWSClient::Subscription: " + result.error_message); + POCOResult const poco_result = client_.httpPost(Services::SUBSCRIPTION, subscription_content.str()); - std::string poll = "/poll/"; - subscription_group_id_ = findSubstringContent(poco_result.poco_info.http.response.header_info, poll, "\n"); - poll += subscription_group_id_; + if (poco_result.poco_info.http.response.status != HTTPResponse::HTTP_CREATED) + throw std::runtime_error("Unable to create Subscription: " + poco_result.poco_info.http.response.content); - p_websocket_ = client_.webSocketConnect(poll, "robapi2_subscription", DEFAULT_SUBSCRIPTION_TIMEOUT); + subscription_group_id_ = findSubstringContent(poco_result.poco_info.http.response.header_info, "/poll/", "\n"); } + SubscriptionGroup::~SubscriptionGroup() + { + // Unsubscribe from events + std::string const uri = Services::SUBSCRIPTION + "/" + subscription_group_id_; + client_.httpDelete(uri); + } + - RWSClient::Subscription::~Subscription() + SubscriptionReceiver::SubscriptionReceiver(POCOClient& client, std::string const& subscription_group_id) + : p_websocket_ {client.webSocketConnect("/poll/" + subscription_group_id, "robapi2_subscription", DEFAULT_SUBSCRIPTION_TIMEOUT)} { - try - { - // Unsubscribe from events - endSubscription(); - } - catch (...) - { - // Catch all exceptions in dtor - } } - bool RWSClient::Subscription::waitForSubscriptionEvent(SubscriptionEvent& event) + SubscriptionReceiver::~SubscriptionReceiver() + { + } + + + bool SubscriptionReceiver::waitForEvent(SubscriptionEvent& event) { WebSocketInfo frame; if (webSocketReceiveFrame(frame)) @@ -115,8 +110,7 @@ namespace abb :: rws event.value = xmlFindTextContent(doc, XMLAttribute {"class", "lvalue"}); - // IMPORTANT: don't use AutoPtr here! Otherwise you will get memory corruption: - // https://github.com/NoMagicAi/monomagic/issues/4893 + // IMPORTANT: don't use AutoPtr here! Otherwise you will get memory corruption. if (Poco::XML::Node const * node = doc->getNodeByPath("html/body/div/ul/li/a")) event.resourceUri = xmlNodeGetAttributeValue(node, "href"); @@ -127,24 +121,11 @@ namespace abb :: rws } - RWSResult RWSClient::Subscription::endSubscription() + bool SubscriptionReceiver::webSocketReceiveFrame(WebSocketInfo& frame) { - RWSResult result; + // Lock the object's mutex. It is released when the method goes out of scope. + std::lock_guard lock {websocket_use_mutex_}; - std::string uri = Services::SUBSCRIPTION + "/" + subscription_group_id_; - - EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = false; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); - - result = client_.evaluatePOCOResult(client_.httpDelete(uri), evaluation_conditions); - - return result; - } - - - bool RWSClient::Subscription::webSocketReceiveFrame(WebSocketInfo& frame) - { // If the connection is still active... if (p_websocket_) { @@ -157,9 +138,9 @@ namespace abb :: rws flags = 0; int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); - std::clog << "RWSClient::Subscription::webSocketReceiveFrame: " << number_of_bytes_received << " bytes received\n"; + // std::clog << "Subscription::webSocketReceiveFrame: " << number_of_bytes_received << " bytes received\n"; content = std::string(websocket_buffer_, number_of_bytes_received); - std::clog << "WebSocket frame received: flags=" << flags << ", content=" << content << std::endl; + // std::clog << "WebSocket frame received: flags=" << flags << ", content=" << content << std::endl; // Check for ping frame. if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) @@ -178,8 +159,8 @@ namespace abb :: rws // according to "The WebSocket Protocol" RFC6455. content.clear(); - // Shutdown and destroy the WebSocket. - webSocketShutdown(); + // Destroy the WebSocket to indicate that the connection is shut down. + p_websocket_.reset(); } frame.flags = flags; @@ -190,15 +171,23 @@ namespace abb :: rws } - void RWSClient::Subscription::webSocketShutdown() + void SubscriptionReceiver::forceClose() + { + webSocketShutdown(); + } + + + void SubscriptionReceiver::webSocketShutdown() { if (p_websocket_) { // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. p_websocket_->shutdown(); - // Destroy the WebSocket. - p_websocket_.release(); + // Also acquire the websocket lock before invalidating the pointer, + // or we will break running calls to webSocketReceiveFrame(). + std::lock_guard use_lock(websocket_use_mutex_); + p_websocket_.reset(); } } From cbb6655ce93c96848127e6e9e6bb7710dba220e5 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sat, 30 Jan 2021 20:00:14 +0100 Subject: [PATCH 10/17] WebSocket code clean-up --- CMakeLists.txt | 1 + include/abb_librws/rws_poco_result.h | 22 ----------- include/abb_librws/rws_subscription.h | 12 +++--- include/abb_librws/rws_websocket.h | 31 ++++++++++++++++ include/abb_librws/rws_websocket_info.h | 23 ------------ src/rws_client.cpp | 4 -- src/rws_poco_result.cpp | 49 ------------------------- src/rws_subscription.cpp | 8 +--- src/rws_websocket.cpp | 48 ++++++++++++++++++++++++ 9 files changed, 88 insertions(+), 110 deletions(-) create mode 100644 include/abb_librws/rws_websocket.h delete mode 100644 include/abb_librws/rws_websocket_info.h create mode 100644 src/rws_websocket.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index ed3be4f3..34b79ea5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -42,6 +42,7 @@ set( src/rws_rapid.cpp src/rws_state_machine_interface.cpp src/rws_subscription.cpp + src/rws_websocket.cpp ) add_library(${PROJECT_NAME} ${SRC_FILES}) diff --git a/include/abb_librws/rws_poco_result.h b/include/abb_librws/rws_poco_result.h index 89ab0b8c..9123d285 100644 --- a/include/abb_librws/rws_poco_result.h +++ b/include/abb_librws/rws_poco_result.h @@ -1,7 +1,5 @@ #pragma once -#include - #include #include @@ -101,11 +99,6 @@ namespace abb :: rws * \brief Container for HTTP info. */ HTTPInfo http; - - /** - * \brief Container for WebSocket info. - */ - WebSocketInfo websocket; }; /** @@ -144,14 +137,6 @@ namespace abb :: rws */ void addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, const std::string& response_content = ""); - /** - * \brief A method for adding info from a received WebSocket frame. - * - * \param flags for the received WebSocket frame's flags. - * \param frame_content for the received WebSocket frame's content. - */ - void addWebSocketFrameInfo(const int flags, const std::string& frame_content); - /** * \brief A method to map the general status to a std::string. * @@ -159,13 +144,6 @@ namespace abb :: rws */ std::string mapGeneralStatus() const; - /** - * \brief A method to map the opcode of a received WebSocket frame. - * - * \return std::string containing the mapped opcode. - */ - std::string mapWebSocketOpcode() const; - /** * \brief A method to construct a text representation of the result. * diff --git a/include/abb_librws/rws_subscription.h b/include/abb_librws/rws_subscription.h index b2168e9e..9d2e9952 100644 --- a/include/abb_librws/rws_subscription.h +++ b/include/abb_librws/rws_subscription.h @@ -2,6 +2,7 @@ #include "rws_resource.h" #include "rws_poco_client.h" +#include "rws_websocket.h" #include @@ -160,7 +161,7 @@ namespace abb :: rws /** - * \brief Receives RWS events. + * \brief Receives RWS subscription events. */ class SubscriptionReceiver { @@ -250,7 +251,7 @@ namespace abb :: rws * * \return true if the connection is still active, false otherwise. */ - bool webSocketReceiveFrame(WebSocketInfo& frame); + bool webSocketReceiveFrame(WebSocketFrame& frame); /** @@ -282,7 +283,7 @@ namespace abb :: rws */ Subscription(POCOClient& client, SubscriptionResources const& resources) : group_ {new SubscriptionGroup {client, resources}} - , receiver_ {new SubscriptionReceiver {client, group_->id()}} + , receiver_ {client, group_->id()} { } @@ -298,7 +299,6 @@ namespace abb :: rws */ ~Subscription() { - } @@ -312,7 +312,7 @@ namespace abb :: rws */ bool waitForEvent(SubscriptionEvent& event) { - return receiver_->waitForEvent(event); + return receiver_.waitForEvent(event); } @@ -328,6 +328,6 @@ namespace abb :: rws private: std::unique_ptr group_; - std::unique_ptr receiver_; + SubscriptionReceiver receiver_; }; } \ No newline at end of file diff --git a/include/abb_librws/rws_websocket.h b/include/abb_librws/rws_websocket.h new file mode 100644 index 00000000..a3918352 --- /dev/null +++ b/include/abb_librws/rws_websocket.h @@ -0,0 +1,31 @@ +#pragma once + +#include + + +namespace abb :: rws +{ + /** + * \brief WebSocket frame. + */ + struct WebSocketFrame + { + /** + * \brief WebSocket frame flags. + */ + int flags = 0; + + /** + * \brief WebSocket frame content. + */ + std::string frame_content; + }; + + + /** + * \brief A method to map the flags of a received WebSocket frame to a string representing the opcode. + * + * \return std::string containing the mapped opcode. + */ + std::string mapWebSocketOpcode(int flags); +} \ No newline at end of file diff --git a/include/abb_librws/rws_websocket_info.h b/include/abb_librws/rws_websocket_info.h deleted file mode 100644 index e5e4688f..00000000 --- a/include/abb_librws/rws_websocket_info.h +++ /dev/null @@ -1,23 +0,0 @@ -#pragma once - -#include - - -namespace abb :: rws -{ - /** - * \brief A struct for containing WebSocket info. - */ - struct WebSocketInfo - { - /** - * \brief Flags from a received WebSocket frame. - */ - int flags = 0; - - /** - * \brief Content from a received WebSocket frame. - */ - std::string frame_content; - }; -} \ No newline at end of file diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 210951c2..4c650d25 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -592,10 +592,6 @@ void RWSClient::parseMessage(RWSResult* result, const POCOResult& poco_result) { ss << poco_result.poco_info.http.response.content; } - else if (!poco_result.poco_info.websocket.frame_content.empty()) - { - ss << poco_result.poco_info.websocket.frame_content; - } else { // XML parsing: Missing message diff --git a/src/rws_poco_result.cpp b/src/rws_poco_result.cpp index 393ca14f..de051600 100644 --- a/src/rws_poco_result.cpp +++ b/src/rws_poco_result.cpp @@ -42,13 +42,6 @@ namespace abb :: rws poco_info.http.response.content = response_content; } - void POCOResult::addWebSocketFrameInfo(const int flags, - const std::string& frame_content) - { - poco_info.websocket.flags = flags; - poco_info.websocket.frame_content = frame_content; - } - /************************************************************ * Auxiliary methods */ @@ -95,44 +88,6 @@ namespace abb :: rws return result; } - std::string POCOResult::mapWebSocketOpcode() const - { - std::string result; - - switch (poco_info.websocket.flags & WebSocket::FRAME_OP_BITMASK) - { - case WebSocket::FRAME_OP_CONT: - result = "FRAME_OP_CONT"; - break; - - case WebSocket::FRAME_OP_TEXT: - result = "FRAME_OP_TEXT"; - break; - - case WebSocket::FRAME_OP_BINARY: - result = "FRAME_OP_BINARY"; - break; - - case WebSocket::FRAME_OP_CLOSE: - result = "FRAME_OP_CLOSE"; - break; - - case WebSocket::FRAME_OP_PING: - result = "FRAME_OP_PING"; - break; - - case WebSocket::FRAME_OP_PONG: - result = "FRAME_OP_PONG"; - break; - - default: - result = "FRAME_OP_UNDEFINED"; - break; - } - - return result; - } - std::string POCOResult::toString(const bool verbose, const size_t indent) const { std::stringstream ss; @@ -156,10 +111,6 @@ namespace abb :: rws } } } - else if (status == OK) - { - ss << seperator << "WebSocket frame: " << mapWebSocketOpcode(); - } return ss.str(); } diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index 5c2c65e4..51125b82 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -1,6 +1,5 @@ #include -#include #include @@ -102,7 +101,7 @@ namespace abb :: rws bool SubscriptionReceiver::waitForEvent(SubscriptionEvent& event) { - WebSocketInfo frame; + WebSocketFrame frame; if (webSocketReceiveFrame(frame)) { // std::clog << "WebSocket frame received: flags=" << frame.flags << ", frame_content=" << frame.frame_content << std::endl; @@ -121,7 +120,7 @@ namespace abb :: rws } - bool SubscriptionReceiver::webSocketReceiveFrame(WebSocketInfo& frame) + bool SubscriptionReceiver::webSocketReceiveFrame(WebSocketFrame& frame) { // Lock the object's mutex. It is released when the method goes out of scope. std::lock_guard lock {websocket_use_mutex_}; @@ -137,10 +136,7 @@ namespace abb :: rws { flags = 0; int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); - - // std::clog << "Subscription::webSocketReceiveFrame: " << number_of_bytes_received << " bytes received\n"; content = std::string(websocket_buffer_, number_of_bytes_received); - // std::clog << "WebSocket frame received: flags=" << flags << ", content=" << content << std::endl; // Check for ping frame. if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) diff --git a/src/rws_websocket.cpp b/src/rws_websocket.cpp new file mode 100644 index 00000000..8ead5de8 --- /dev/null +++ b/src/rws_websocket.cpp @@ -0,0 +1,48 @@ +#include + +#include + + +namespace abb :: rws +{ + using Poco::Net::WebSocket; + + + std::string mapWebSocketOpcode(int flags) + { + std::string result; + + switch (flags & WebSocket::FRAME_OP_BITMASK) + { + case WebSocket::FRAME_OP_CONT: + result = "FRAME_OP_CONT"; + break; + + case WebSocket::FRAME_OP_TEXT: + result = "FRAME_OP_TEXT"; + break; + + case WebSocket::FRAME_OP_BINARY: + result = "FRAME_OP_BINARY"; + break; + + case WebSocket::FRAME_OP_CLOSE: + result = "FRAME_OP_CLOSE"; + break; + + case WebSocket::FRAME_OP_PING: + result = "FRAME_OP_PING"; + break; + + case WebSocket::FRAME_OP_PONG: + result = "FRAME_OP_PONG"; + break; + + default: + result = "FRAME_OP_UNDEFINED"; + break; + } + + return result; + } +} \ No newline at end of file From 98cb5d365af6792505a99916b7b84b1e0cd01097 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sat, 30 Jan 2021 21:02:07 +0100 Subject: [PATCH 11/17] Added WebSocket class --- include/abb_librws/rws_poco_client.h | 3 +- include/abb_librws/rws_subscription.h | 46 +------------- include/abb_librws/rws_websocket.h | 79 ++++++++++++++++++++++++ src/rws_poco_client.cpp | 6 +- src/rws_subscription.cpp | 68 +-------------------- src/rws_websocket.cpp | 87 +++++++++++++++++++++++++-- 6 files changed, 169 insertions(+), 120 deletions(-) diff --git a/include/abb_librws/rws_poco_client.h b/include/abb_librws/rws_poco_client.h index 0c69232e..d30f1e69 100644 --- a/include/abb_librws/rws_poco_client.h +++ b/include/abb_librws/rws_poco_client.h @@ -141,13 +141,12 @@ namespace rws * * \param uri for the URI (path and query). * \param protocol for the WebSocket protocol. - * \param timeout for the WebSocket communication timeout [microseconds]. * * \return Pointer to a client WebSocket. * * \throw \a std::runtime_error if something goes wrong */ - std::unique_ptr webSocketConnect(const std::string& uri, const std::string& protocol, const Poco::Int64 timeout); + std::unique_ptr webSocketConnect(const std::string& uri, const std::string& protocol); private: diff --git a/include/abb_librws/rws_subscription.h b/include/abb_librws/rws_subscription.h index 9d2e9952..806272b7 100644 --- a/include/abb_librws/rws_subscription.h +++ b/include/abb_librws/rws_subscription.h @@ -8,7 +8,6 @@ #include #include -#include namespace abb :: rws @@ -215,57 +214,16 @@ namespace abb :: rws */ static constexpr Poco::Int64 DEFAULT_SUBSCRIPTION_TIMEOUT = 40e6; - /** - * \brief Static constant for the socket's buffer size. - */ - static const size_t BUFFER_SIZE = 1024; - - /** - * \brief A buffer for a Subscription. - */ - char websocket_buffer_[BUFFER_SIZE]; /** - * \brief A mutex for protecting the client's WebSocket resources. - * - * This mutex must be held while using the p_websocket_ member, - * and while invalidating the pointer. + * \brief WebSocket for receiving events. */ - std::mutex websocket_use_mutex_; - - /** - * \brief A pointer to a Subscription client. - */ - std::unique_ptr p_websocket_; + WebSocket webSocket_; /** * \brief Parser for XML in WebSocket frames. */ Poco::XML::DOMParser parser_; - - - /** - * \brief A method for receiving a WebSocket frame. - * - * \brief frame the received frame - * - * \return true if the connection is still active, false otherwise. - */ - bool webSocketReceiveFrame(WebSocketFrame& frame); - - - /** - * \brief Forcibly shut down the websocket connection. - * - * The connection is shut down immediately. - * Subsequently, the function will block until a current call to webSocketReceiveFrame() has finished, - * before cleaning up the local state. - * - * Note that since mutexes do not guarantee the order of acquisition for multiple contenders, - * it is undefined how many calls to webSocketReceiveFrame() will still attempt to use the shut down - * connection before the local state is cleaned. Those invocation will throw a runtime error. - */ - void webSocketShutdown(); }; diff --git a/include/abb_librws/rws_websocket.h b/include/abb_librws/rws_websocket.h index a3918352..5004f95b 100644 --- a/include/abb_librws/rws_websocket.h +++ b/include/abb_librws/rws_websocket.h @@ -1,6 +1,12 @@ #pragma once +#include "rws_poco_client.h" + +#include + #include +#include +#include namespace abb :: rws @@ -28,4 +34,77 @@ namespace abb :: rws * \return std::string containing the mapped opcode. */ std::string mapWebSocketOpcode(int flags); + + + /** + * \brief Manages a WebSocket connection. + */ + class WebSocket + { + public: + /** + * \brief Connects to a WebSocket. + * + * \param client \a POCOClient for HTTP request. + * \param uri for the URI (path and query). + * \param protocol for the WebSocket protocol. + * \param timeout for the WebSocket communication timeout [microseconds]. + * + * \return Pointer to a client WebSocket. + * + * \throw \a std::runtime_error if something goes wrong + */ + WebSocket(POCOClient& client, std::string const& uri, std::string const& protocol, Poco::Int64 timeout); + + ~WebSocket(); + + + /** + * \brief A method for receiving a WebSocket frame. + * + * \brief frame the received frame + * + * \return true if the connection is still active, false otherwise. + */ + bool receiveFrame(WebSocketFrame& frame); + + + /** + * \brief Forcibly shut down the websocket connection. + * + * The connection is shut down immediately. + * Subsequently, the function will block until a current call to receiveFrame() has finished, + * before cleaning up the local state. + * + * Note that since mutexes do not guarantee the order of acquisition for multiple contenders, + * it is undefined how many calls to receiveFrame() will still attempt to use the shut down + * connection before the local state is cleaned. Those invocation will throw a runtime error. + */ + void shutdown(); + + + private: + /** + * \brief Static constant for the socket's buffer size. + */ + static const size_t BUFFER_SIZE = 1024; + + /** + * \brief A buffer for a Subscription. + */ + char websocket_buffer_[BUFFER_SIZE]; + + /** + * \brief A mutex for protecting the client's WebSocket resources. + * + * This mutex must be held while using the p_websocket_ member, + * and while invalidating the pointer. + */ + std::mutex websocket_use_mutex_; + + /** + * \brief A pointer to a Subscription client. + */ + std::unique_ptr p_websocket_; + }; } \ No newline at end of file diff --git a/src/rws_poco_client.cpp b/src/rws_poco_client.cpp index 8bf25414..d83e4602 100644 --- a/src/rws_poco_client.cpp +++ b/src/rws_poco_client.cpp @@ -160,8 +160,7 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, std::unique_ptr POCOClient::webSocketConnect(const std::string& uri, - const std::string& protocol, - const Poco::Int64 timeout) + const std::string& protocol) { // Lock the object's mutex. It is released when the method goes out of scope. ScopedLock lock(http_mutex_); @@ -178,8 +177,7 @@ std::unique_ptr POCOClient::webSocketConnect(const std::st std::unique_ptr websocket {new WebSocket {http_client_session_, request, response}}; if (response.getStatus() != HTTPResponse::HTTP_SWITCHING_PROTOCOLS) throw std::runtime_error("webSocketConnect() failed: HTTP response " + std::to_string(response.getStatus())); - - websocket->setReceiveTimeout(Poco::Timespan(timeout)); + return websocket; } catch (std::exception const& e) diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index 51125b82..5cb99e1c 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -89,7 +89,7 @@ namespace abb :: rws SubscriptionReceiver::SubscriptionReceiver(POCOClient& client, std::string const& subscription_group_id) - : p_websocket_ {client.webSocketConnect("/poll/" + subscription_group_id, "robapi2_subscription", DEFAULT_SUBSCRIPTION_TIMEOUT)} + : webSocket_ {client, "/poll/" + subscription_group_id, "robapi2_subscription", DEFAULT_SUBSCRIPTION_TIMEOUT} { } @@ -102,7 +102,7 @@ namespace abb :: rws bool SubscriptionReceiver::waitForEvent(SubscriptionEvent& event) { WebSocketFrame frame; - if (webSocketReceiveFrame(frame)) + if (webSocket_.receiveFrame(frame)) { // std::clog << "WebSocket frame received: flags=" << frame.flags << ", frame_content=" << frame.frame_content << std::endl; Poco::AutoPtr doc = parser_.parseString(frame.frame_content); @@ -120,71 +120,9 @@ namespace abb :: rws } - bool SubscriptionReceiver::webSocketReceiveFrame(WebSocketFrame& frame) - { - // Lock the object's mutex. It is released when the method goes out of scope. - std::lock_guard lock {websocket_use_mutex_}; - - // If the connection is still active... - if (p_websocket_) - { - int flags = 0; - std::string content; - - // Wait for (non-ping) WebSocket frames. - do - { - flags = 0; - int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); - content = std::string(websocket_buffer_, number_of_bytes_received); - - // Check for ping frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) - { - // Reply with a pong frame. - p_websocket_->sendFrame(websocket_buffer_, - number_of_bytes_received, - WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); - } - } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); - - // Check for closing frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) - { - // Do not pass content of a closing frame to end user, - // according to "The WebSocket Protocol" RFC6455. - content.clear(); - - // Destroy the WebSocket to indicate that the connection is shut down. - p_websocket_.reset(); - } - - frame.flags = flags; - frame.frame_content = content; - } - - return (bool)p_websocket_; - } - - void SubscriptionReceiver::forceClose() { - webSocketShutdown(); - } - - - void SubscriptionReceiver::webSocketShutdown() - { - if (p_websocket_) - { - // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. - p_websocket_->shutdown(); - - // Also acquire the websocket lock before invalidating the pointer, - // or we will break running calls to webSocketReceiveFrame(). - std::lock_guard use_lock(websocket_use_mutex_); - p_websocket_.reset(); - } + webSocket_.shutdown(); } diff --git a/src/rws_websocket.cpp b/src/rws_websocket.cpp index 8ead5de8..0f6803ed 100644 --- a/src/rws_websocket.cpp +++ b/src/rws_websocket.cpp @@ -1,15 +1,12 @@ #include -#include - namespace abb :: rws { - using Poco::Net::WebSocket; - - std::string mapWebSocketOpcode(int flags) { + using Poco::Net::WebSocket; + std::string result; switch (flags & WebSocket::FRAME_OP_BITMASK) @@ -45,4 +42,84 @@ namespace abb :: rws return result; } + + + WebSocket::WebSocket(POCOClient& client, std::string const& uri, std::string const& protocol, Poco::Int64 timeout) + : p_websocket_ {client.webSocketConnect(uri, protocol)} + { + p_websocket_->setReceiveTimeout(Poco::Timespan(timeout)); + } + + + WebSocket::~WebSocket() + { + shutdown(); + } + + + bool WebSocket::receiveFrame(WebSocketFrame& frame) + { + using Poco::Net::WebSocket; + + // Lock the object's mutex. It is released when the method goes out of scope. + std::lock_guard lock {websocket_use_mutex_}; + + // If the connection is still active... + if (p_websocket_) + { + int flags = 0; + std::string content; + + // Wait for (non-ping) WebSocket frames. + do + { + flags = 0; + int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); + content = std::string(websocket_buffer_, number_of_bytes_received); + + // Check for ping frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) + { + // Reply with a pong frame. + p_websocket_->sendFrame(websocket_buffer_, + number_of_bytes_received, + WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); + } + } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); + + // Check for closing frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) + { + // Do not pass content of a closing frame to end user, + // according to "The WebSocket Protocol" RFC6455. + content.clear(); + + // Shutdown the WebSocket. + p_websocket_->shutdown(); + + // Destroy the WebSocket to indicate that the connection is shut down. + p_websocket_.reset(); + } + + frame.flags = flags; + frame.frame_content = content; + } + + return (bool)p_websocket_; + } + + + void WebSocket::shutdown() + { + if (p_websocket_) + { + // Shut down the socket. This should make receiveFrame() return as soon as possible. + p_websocket_->shutdown(); + + // Also acquire the websocket lock before invalidating the pointer, + // or we will break running calls to receiveFrame(). + std::lock_guard use_lock {websocket_use_mutex_}; + p_websocket_.reset(); + } + } } \ No newline at end of file From 7c89d97a2ce405de8fd33f25dc1868ad9d4de968 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sun, 31 Jan 2021 11:24:39 +0100 Subject: [PATCH 12/17] Removed the custom WebSocket class --- include/abb_librws/rws_interface.h | 6 +- include/abb_librws/rws_poco_client.h | 4 +- include/abb_librws/rws_subscription.h | 102 +++++++++----------------- include/abb_librws/rws_websocket.h | 79 -------------------- src/rws_interface.cpp | 2 +- src/rws_poco_client.cpp | 4 +- src/rws_subscription.cpp | 63 ++++++++++++++-- src/rws_websocket.cpp | 82 +-------------------- 8 files changed, 104 insertions(+), 238 deletions(-) diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index d8e4183e..1e269ade 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -798,15 +798,15 @@ class RWSInterface bool deleteFile(const FileResource& resource); /** - * \brief A method for starting for a subscription. + * \brief Creates a subscription group. * * \param resources specifying the resources to subscribe to. * - * \return \a Subscription object. + * \return Newly created \a SubscriptionGroup for specified subscription resources. * * \throw \a std::runtime_error if something goes wrong */ - Subscription startSubscription(const SubscriptionResources& resources); + SubscriptionGroup openSubscription(const SubscriptionResources& resources); /** * \brief A method for registering a user as local. diff --git a/include/abb_librws/rws_poco_client.h b/include/abb_librws/rws_poco_client.h index d30f1e69..a05c7522 100644 --- a/include/abb_librws/rws_poco_client.h +++ b/include/abb_librws/rws_poco_client.h @@ -142,11 +142,11 @@ namespace rws * \param uri for the URI (path and query). * \param protocol for the WebSocket protocol. * - * \return Pointer to a client WebSocket. + * \return Newly created client WebSocket. * * \throw \a std::runtime_error if something goes wrong */ - std::unique_ptr webSocketConnect(const std::string& uri, const std::string& protocol); + Poco::Net::WebSocket webSocketConnect(const std::string& uri, const std::string& protocol); private: diff --git a/include/abb_librws/rws_subscription.h b/include/abb_librws/rws_subscription.h index 806272b7..e4251e88 100644 --- a/include/abb_librws/rws_subscription.h +++ b/include/abb_librws/rws_subscription.h @@ -134,6 +134,13 @@ namespace abb :: rws */ SubscriptionGroup(POCOClient& client, SubscriptionResources const& resources); + + /** + * \a SubscriptionGroup objects are moveable, but not copyable. + */ + SubscriptionGroup(SubscriptionGroup&&) = default; + + /** * \brief Ends an active subscription. */ @@ -149,6 +156,15 @@ namespace abb :: rws return subscription_group_id_; } + + /** + * \brief Establish WebSocket connection to receive subscription events. + * + * \return A WebSocket that will receive the subscription events. + */ + Poco::Net::WebSocket connect() const; + + private: POCOClient& client_; @@ -169,10 +185,9 @@ namespace abb :: rws * \brief Establishes WebSocket connection with the server and prepares to receive events * for a specified subscription group. * - * \param client \a POCOClient used to establish WebSocket connection. - * \param subscription_group_id ID of the subscription group to receive events for. + * \param group Subscription group to receive events for. */ - SubscriptionReceiver(POCOClient& client, std::string const& subscription_group_id); + SubscriptionReceiver(SubscriptionGroup const& group); /** @@ -186,106 +201,61 @@ namespace abb :: rws * * \param event event data * - * \return true if the connection is still alive, false if the connection - * has been closed by removing the subscription. + * \return true if the connection is still alive, false if the connection has been closed. */ bool waitForEvent(SubscriptionEvent& event); /** - * \brief Force close the active subscription connection. + * \brief Shutdown the active subscription connection. * - * This will cause waitForEvent() to return or throw. + * If waitForEvent() is being executed on a different thread, it will return or throw. * It does not delete the subscription from the controller. * * The preferred way to close the subscription is the destruction of the \a SubscriptionGroup object. * This function can be used to force the connection to close immediately in * case the robot controller is not responding. * - * This function blocks until an active waitForEvent() has finished. + * This function will return immediately and does not block until an active waitForEvent() has finished. * */ - void forceClose(); + void shutdown(); private: /** * \brief Default RWS subscription timeout [microseconds]. */ - static constexpr Poco::Int64 DEFAULT_SUBSCRIPTION_TIMEOUT = 40e6; - + static const Poco::Timespan DEFAULT_SUBSCRIPTION_TIMEOUT; /** - * \brief WebSocket for receiving events. + * \brief Static constant for the socket's buffer size. */ - WebSocket webSocket_; + static const size_t BUFFER_SIZE = 1024; /** - * \brief Parser for XML in WebSocket frames. - */ - Poco::XML::DOMParser parser_; - }; - - - /** - * \brief Manages RWS event subscription. - */ - class Subscription - { - public: - /** - * \brief A constructor. - * - * \param client a client to subscribe - * \param resources list of resources to subscribe + * \brief A buffer for a Subscription. */ - Subscription(POCOClient& client, SubscriptionResources const& resources) - : group_ {new SubscriptionGroup {client, resources}} - , receiver_ {client, group_->id()} - { - } - + char websocket_buffer_[BUFFER_SIZE]; /** - * \brief No copy constructor. + * \brief WebSocket for receiving events. */ - Subscription(Subscription const&) = delete; - + Poco::Net::WebSocket webSocket_; /** - * \brief Ends an active subscription. + * \brief Parser for XML in WebSocket frames. */ - ~Subscription() - { - } + Poco::XML::DOMParser parser_; /** - * \brief Waits for a subscription event. + * \brief A method for receiving a WebSocket frame. * - * \param event event data + * \brief frame the received frame * - * \return true if the connection is still alive, false if the connection - * has been closed by removing the subscription. - */ - bool waitForEvent(SubscriptionEvent& event) - { - return receiver_.waitForEvent(event); - } - - - /** - * \brief Ends an active subscription but does not destroy the receiver, - * s.t. if waitForEvent() is being executed in another thread it can exit gracefully. + * \return true if the connection is still active, false otherwise. */ - void endSubscription() - { - group_.reset(); - } - - - private: - std::unique_ptr group_; - SubscriptionReceiver receiver_; + bool webSocketReceiveFrame(WebSocketFrame& frame); }; } \ No newline at end of file diff --git a/include/abb_librws/rws_websocket.h b/include/abb_librws/rws_websocket.h index 5004f95b..a3918352 100644 --- a/include/abb_librws/rws_websocket.h +++ b/include/abb_librws/rws_websocket.h @@ -1,12 +1,6 @@ #pragma once -#include "rws_poco_client.h" - -#include - #include -#include -#include namespace abb :: rws @@ -34,77 +28,4 @@ namespace abb :: rws * \return std::string containing the mapped opcode. */ std::string mapWebSocketOpcode(int flags); - - - /** - * \brief Manages a WebSocket connection. - */ - class WebSocket - { - public: - /** - * \brief Connects to a WebSocket. - * - * \param client \a POCOClient for HTTP request. - * \param uri for the URI (path and query). - * \param protocol for the WebSocket protocol. - * \param timeout for the WebSocket communication timeout [microseconds]. - * - * \return Pointer to a client WebSocket. - * - * \throw \a std::runtime_error if something goes wrong - */ - WebSocket(POCOClient& client, std::string const& uri, std::string const& protocol, Poco::Int64 timeout); - - ~WebSocket(); - - - /** - * \brief A method for receiving a WebSocket frame. - * - * \brief frame the received frame - * - * \return true if the connection is still active, false otherwise. - */ - bool receiveFrame(WebSocketFrame& frame); - - - /** - * \brief Forcibly shut down the websocket connection. - * - * The connection is shut down immediately. - * Subsequently, the function will block until a current call to receiveFrame() has finished, - * before cleaning up the local state. - * - * Note that since mutexes do not guarantee the order of acquisition for multiple contenders, - * it is undefined how many calls to receiveFrame() will still attempt to use the shut down - * connection before the local state is cleaned. Those invocation will throw a runtime error. - */ - void shutdown(); - - - private: - /** - * \brief Static constant for the socket's buffer size. - */ - static const size_t BUFFER_SIZE = 1024; - - /** - * \brief A buffer for a Subscription. - */ - char websocket_buffer_[BUFFER_SIZE]; - - /** - * \brief A mutex for protecting the client's WebSocket resources. - * - * This mutex must be held while using the p_websocket_ member, - * and while invalidating the pointer. - */ - std::mutex websocket_use_mutex_; - - /** - * \brief A pointer to a Subscription client. - */ - std::unique_ptr p_websocket_; - }; } \ No newline at end of file diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index 503e2f4a..2229299e 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -993,7 +993,7 @@ bool RWSInterface::deleteFile(const FileResource& resource) return rws_client_.deleteFile(resource).success; } -Subscription RWSInterface::startSubscription (const SubscriptionResources& resources) +SubscriptionGroup RWSInterface::openSubscription (const SubscriptionResources& resources) { return {rws_client_, resources}; } diff --git a/src/rws_poco_client.cpp b/src/rws_poco_client.cpp index d83e4602..64a9d6db 100644 --- a/src/rws_poco_client.cpp +++ b/src/rws_poco_client.cpp @@ -159,7 +159,7 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, } -std::unique_ptr POCOClient::webSocketConnect(const std::string& uri, +Poco::Net::WebSocket POCOClient::webSocketConnect(const std::string& uri, const std::string& protocol) { // Lock the object's mutex. It is released when the method goes out of scope. @@ -174,7 +174,7 @@ std::unique_ptr POCOClient::webSocketConnect(const std::st // Attempt the communication. try { - std::unique_ptr websocket {new WebSocket {http_client_session_, request, response}}; + Poco::Net::WebSocket websocket {http_client_session_, request, response}; if (response.getStatus() != HTTPResponse::HTTP_SWITCHING_PROTOCOLS) throw std::runtime_error("webSocketConnect() failed: HTTP response " + std::to_string(response.getStatus())); diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index 5cb99e1c..34c6b5c5 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -12,7 +12,7 @@ namespace abb :: rws typedef SystemConstants::RWS::Identifiers Identifiers; typedef SystemConstants::RWS::Services Services; - + /*********************************************************************************************************************** * Class definitions: SubscriptionResources */ @@ -88,9 +88,19 @@ namespace abb :: rws } - SubscriptionReceiver::SubscriptionReceiver(POCOClient& client, std::string const& subscription_group_id) - : webSocket_ {client, "/poll/" + subscription_group_id, "robapi2_subscription", DEFAULT_SUBSCRIPTION_TIMEOUT} + Poco::Net::WebSocket SubscriptionGroup::connect() const + { + return client_.webSocketConnect("/poll/" + subscription_group_id_, "robapi2_subscription"); + } + + + const Poco::Timespan SubscriptionReceiver::DEFAULT_SUBSCRIPTION_TIMEOUT {40000000000}; + + + SubscriptionReceiver::SubscriptionReceiver(SubscriptionGroup const& group) + : webSocket_ {group.connect()} { + webSocket_.setReceiveTimeout(DEFAULT_SUBSCRIPTION_TIMEOUT); } @@ -102,7 +112,7 @@ namespace abb :: rws bool SubscriptionReceiver::waitForEvent(SubscriptionEvent& event) { WebSocketFrame frame; - if (webSocket_.receiveFrame(frame)) + if (webSocketReceiveFrame(frame)) { // std::clog << "WebSocket frame received: flags=" << frame.flags << ", frame_content=" << frame.frame_content << std::endl; Poco::AutoPtr doc = parser_.parseString(frame.frame_content); @@ -120,8 +130,51 @@ namespace abb :: rws } - void SubscriptionReceiver::forceClose() + bool SubscriptionReceiver::webSocketReceiveFrame(WebSocketFrame& frame) + { + // If the connection is still active... + int flags = 0; + std::string content; + int number_of_bytes_received = 0; + + // Wait for (non-ping) WebSocket frames. + do + { + flags = 0; + number_of_bytes_received = webSocket_.receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); + content = std::string(websocket_buffer_, number_of_bytes_received); + + // Check for ping frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) + { + // Reply with a pong frame. + webSocket_.sendFrame(websocket_buffer_, + number_of_bytes_received, + WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); + } + } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); + + // Check for closing frame. + if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) + { + // Do not pass content of a closing frame to end user, + // according to "The WebSocket Protocol" RFC6455. + frame.frame_content.clear(); + frame.flags = flags; + + return false; + } + + frame.flags = flags; + frame.frame_content = content; + + return number_of_bytes_received != 0; + } + + + void SubscriptionReceiver::shutdown() { + // Shut down the socket. This should make webSocketReceiveFrame() return as soon as possible. webSocket_.shutdown(); } diff --git a/src/rws_websocket.cpp b/src/rws_websocket.cpp index 0f6803ed..ccd961cb 100644 --- a/src/rws_websocket.cpp +++ b/src/rws_websocket.cpp @@ -1,5 +1,7 @@ #include +#include + namespace abb :: rws { @@ -42,84 +44,4 @@ namespace abb :: rws return result; } - - - WebSocket::WebSocket(POCOClient& client, std::string const& uri, std::string const& protocol, Poco::Int64 timeout) - : p_websocket_ {client.webSocketConnect(uri, protocol)} - { - p_websocket_->setReceiveTimeout(Poco::Timespan(timeout)); - } - - - WebSocket::~WebSocket() - { - shutdown(); - } - - - bool WebSocket::receiveFrame(WebSocketFrame& frame) - { - using Poco::Net::WebSocket; - - // Lock the object's mutex. It is released when the method goes out of scope. - std::lock_guard lock {websocket_use_mutex_}; - - // If the connection is still active... - if (p_websocket_) - { - int flags = 0; - std::string content; - - // Wait for (non-ping) WebSocket frames. - do - { - flags = 0; - int number_of_bytes_received = p_websocket_->receiveFrame(websocket_buffer_, sizeof(websocket_buffer_), flags); - content = std::string(websocket_buffer_, number_of_bytes_received); - - // Check for ping frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING) - { - // Reply with a pong frame. - p_websocket_->sendFrame(websocket_buffer_, - number_of_bytes_received, - WebSocket::FRAME_FLAG_FIN | WebSocket::FRAME_OP_PONG); - } - } while ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_PING); - - // Check for closing frame. - if ((flags & WebSocket::FRAME_OP_BITMASK) == WebSocket::FRAME_OP_CLOSE) - { - // Do not pass content of a closing frame to end user, - // according to "The WebSocket Protocol" RFC6455. - content.clear(); - - // Shutdown the WebSocket. - p_websocket_->shutdown(); - - // Destroy the WebSocket to indicate that the connection is shut down. - p_websocket_.reset(); - } - - frame.flags = flags; - frame.frame_content = content; - } - - return (bool)p_websocket_; - } - - - void WebSocket::shutdown() - { - if (p_websocket_) - { - // Shut down the socket. This should make receiveFrame() return as soon as possible. - p_websocket_->shutdown(); - - // Also acquire the websocket lock before invalidating the pointer, - // or we will break running calls to receiveFrame(). - std::lock_guard use_lock {websocket_use_mutex_}; - p_websocket_.reset(); - } - } } \ No newline at end of file From 74c08210b6bdd8923c9615573536f3293c1ae42a Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Sun, 31 Jan 2021 12:34:45 +0100 Subject: [PATCH 13/17] Passing exceptions from POCOClient::makeHTTPRequest() to the caller. --- include/abb_librws/rws_common.h | 15 ++++++++ include/abb_librws/rws_poco_client.h | 14 -------- src/rws_client.cpp | 6 ++++ src/rws_common.cpp | 31 +++++++++++++++++ src/rws_poco_client.cpp | 52 ++-------------------------- 5 files changed, 55 insertions(+), 63 deletions(-) diff --git a/include/abb_librws/rws_common.h b/include/abb_librws/rws_common.h index 52b823e4..634bd2fc 100644 --- a/include/abb_librws/rws_common.h +++ b/include/abb_librws/rws_common.h @@ -151,6 +151,21 @@ bool xmlNodeHasAttribute(const Poco::XML::Node* p_node, const XMLAttribute& attr */ bool xmlNodeHasAttribute(const Poco::XML::Node* p_node, const std::string& name, const std::string& value); + +/** + * \brief A function for retrieving a substring in a string. + * + * \param whole_string for the string containing the substring. + * \param substring_start start of the substring. + * \param substring_end end of the substring. + * + * \return string containing the substring. + */ +std::string findSubstringContent(const std::string& whole_string, + const std::string& substring_start, + const std::string& substring_end); + + /** * \brief Struct containing various constant values defined by default robot controller systems. */ diff --git a/include/abb_librws/rws_poco_client.h b/include/abb_librws/rws_poco_client.h index a05c7522..fd6e5d6d 100644 --- a/include/abb_librws/rws_poco_client.h +++ b/include/abb_librws/rws_poco_client.h @@ -222,20 +222,6 @@ namespace rws */ Poco::Net::NameValueCollection cookies_; }; - - - /** - * \brief A function for retrieving a substring in a string. - * - * \param whole_string for the string containing the substring. - * \param substring_start start of the substring. - * \param substring_end end of the substring. - * - * \return string containing the substring. - */ - std::string findSubstringContent(const std::string& whole_string, - const std::string& substring_start, - const std::string& substring_end); } // end namespace rws } // end namespace abb diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 4c650d25..3a11c815 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -547,6 +547,12 @@ RWSResult RWSClient::evaluatePOCOResult(const POCOResult& poco_result, checkAcceptedOutcomes(&result, poco_result, conditions); + if (poco_result.status != POCOResult::OK) + { + result.success = false; + result.error_message = poco_result.exception_message; + } + if (result.success && conditions.parse_message_into_xml) { parseMessage(&result, poco_result); diff --git a/src/rws_common.cpp b/src/rws_common.cpp index 56a37c8f..9f71144f 100644 --- a/src/rws_common.cpp +++ b/src/rws_common.cpp @@ -201,6 +201,37 @@ bool xmlNodeHasAttribute(const Poco::XML::Node* p_node, const std::string& name, } +std::string findSubstringContent(const std::string& whole_string, + const std::string& substring_start, + const std::string& substring_end) +{ + std::string result; + size_t start_postion = whole_string.find(substring_start); + + if (start_postion != std::string::npos) + { + start_postion += substring_start.size(); + size_t end_postion = whole_string.find_first_of(substring_end, start_postion); + + if (end_postion != std::string::npos) + { + result = whole_string.substr(start_postion, end_postion - start_postion); + } + } + + std::string quot = """; + size_t quot_position = 0; + do + { + quot_position = result.find(quot); + if (quot_position != std::string::npos) + { + result.replace(quot_position, quot.size(), ""); + } + } while (quot_position != std::string::npos); + + return result; +} /*********************************************************************************************************************** diff --git a/src/rws_poco_client.cpp b/src/rws_poco_client.cpp index 64a9d6db..1f47c12e 100644 --- a/src/rws_poco_client.cpp +++ b/src/rws_poco_client.cpp @@ -133,26 +133,12 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, result.status = POCOResult::OK; } - catch (InvalidArgumentException& e) - { - result.status = POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT; - result.exception_message = e.displayText(); - } - catch (TimeoutException& e) - { - result.status = POCOResult::EXCEPTION_POCO_TIMEOUT; - result.exception_message = e.displayText(); - } - catch (NetException& e) - { - result.status = POCOResult::EXCEPTION_POCO_NET; - result.exception_message = e.displayText(); - } - - if (result.status != POCOResult::OK) + catch (Poco::Exception const&) { cookies_.clear(); http_client_session_.reset(); + + throw; } return result; @@ -248,37 +234,5 @@ void POCOClient::extractAndStoreCookie(const std::string& cookie_string) } } -std::string findSubstringContent(const std::string& whole_string, - const std::string& substring_start, - const std::string& substring_end) -{ - std::string result; - size_t start_postion = whole_string.find(substring_start); - - if (start_postion != std::string::npos) - { - start_postion += substring_start.size(); - size_t end_postion = whole_string.find_first_of(substring_end, start_postion); - - if (end_postion != std::string::npos) - { - result = whole_string.substr(start_postion, end_postion - start_postion); - } - } - - std::string quot = """; - size_t quot_position = 0; - do - { - quot_position = result.find(quot); - if (quot_position != std::string::npos) - { - result.replace(quot_position, quot.size(), ""); - } - } while (quot_position != std::string::npos); - - return result; -} - } // end namespace rws } // end namespace abb From 0727fae453a271813348ef61f4478d399377b9d9 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Mon, 1 Feb 2021 14:05:46 +0100 Subject: [PATCH 14/17] Switched to exception-based error handling, removed error codes and exception messages from RWSResult and POCOResult. --- CMakeLists.txt | 1 + include/abb_librws/rws_client.h | 126 +--- include/abb_librws/rws_interface.h | 108 +--- include/abb_librws/rws_poco_client.h | 135 +++- include/abb_librws/rws_poco_result.h | 151 +---- .../abb_librws/rws_state_machine_interface.h | 300 +++------ src/rws_client.cpp | 231 +++---- src/rws_interface.cpp | 439 ++++++------- src/rws_poco_client.cpp | 130 +++- src/rws_poco_result.cpp | 105 +-- src/rws_state_machine_interface.cpp | 611 ++++++++---------- src/rws_subscription.cpp | 21 +- 12 files changed, 988 insertions(+), 1370 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 34b79ea5..9acd8593 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,5 @@ cmake_minimum_required(VERSION 3.5) +set(CMAKE_CXX_STANDARD 17) # Read version from the package.xml file. file(READ ${CMAKE_CURRENT_SOURCE_DIR}/package.xml package_xml_str) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index f22e3be6..812b4e47 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -37,7 +37,6 @@ #ifndef RWS_CLIENT_H #define RWS_CLIENT_H -#include #include #include @@ -56,28 +55,7 @@ namespace rws /** * \brief A struct for containing an evaluated communication result. */ -struct RWSResult -{ - /** - * \brief For indicating if the communication was successfull or not. - */ - bool success; - - /** - * \brief For containing any parsed result in XML format. If no data is parsed, then it will be null. - */ - Poco::AutoPtr p_xml_document; - - /** - * \brief Container for an error message (if one occurred). - */ - std::string error_message; - - /** - * \brief A default constructor. - */ - RWSResult() : success(false) {} -}; +using RWSResult = Poco::AutoPtr; /** @@ -169,12 +147,9 @@ class RWSClient : public POCOClient {} /** - * \brief A destructor. + * \brief Logs out the currently active RWS session. */ - ~RWSClient() - { - logout(); - } + ~RWSClient(); /** * \brief Retrieves a list of controller resources (e.g. controller identity and clock information). @@ -264,11 +239,9 @@ class RWSClient : public POCOClient * \brief A method for retrieving the data of a RAPID symbol (parsed into a struct representing the RAPID data). * * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. - * \param p_data for containing the retrieved data. - * - * \return RWSResult containing the result. + * \param data for containing the retrieved data. */ - RWSResult getRAPIDSymbolData(const RAPIDResource& resource, RAPIDSymbolDataAbstract* p_data); + void getRAPIDSymbolData(const RAPIDResource& resource, RAPIDSymbolDataAbstract& data); /** * \brief A method for retrieving the properties of a RAPID symbol. @@ -335,65 +308,49 @@ class RWSClient : public POCOClient * * \param iosignal for the IO signal's name. * \param value for the IO signal's new value. - * - * \return RWSResult containing the result. */ - RWSResult setIOSignal(const std::string& iosignal, const std::string& value); + void setIOSignal(const std::string& iosignal, const std::string& value); /** * \brief A method for setting the data of a RAPID symbol. * * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. * \param data for the RAPID symbol's new data. - * - * \return RWSResult containing the result. */ - RWSResult setRAPIDSymbolData(const RAPIDResource& resource, const std::string& data); + void setRAPIDSymbolData(const RAPIDResource& resource, const std::string& data); /** * \brief A method for setting the data of a RAPID symbol (based on the provided struct representing the RAPID data). * * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. * \param data for the RAPID symbol's new data. - * - * \return RWSResult containing the result. */ - RWSResult setRAPIDSymbolData(const RAPIDResource& resource, const RAPIDSymbolDataAbstract& data); + void setRAPIDSymbolData(const RAPIDResource& resource, const RAPIDSymbolDataAbstract& data); /** * \brief A method for starting RAPID execution in the robot controller. - * - * \return RWSResult containing the result. */ - RWSResult startRAPIDExecution(); + void startRAPIDExecution(); /** * \brief A method for stopping RAPID execution in the robot controller. - * - * \return RWSResult containing the result. */ - RWSResult stopRAPIDExecution(); + void stopRAPIDExecution(); /** * \brief A method for reseting the RAPID program pointer in the robot controller. - * - * \return RWSResult containing the result. */ - RWSResult resetRAPIDProgramPointer(); + void resetRAPIDProgramPointer(); /** * \brief A method for turning on the robot controller's motors. - * - * \return RWSResult containing the result. */ - RWSResult setMotorsOn(); + void setMotorsOn(); /** * \brief A method for turning off the robot controller's motors. - * - * \return RWSResult containing the result. */ - RWSResult setMotorsOff(); + void setMotorsOff(); /** * \brief A method for setting the robot controller's speed ratio for RAPID motions (e.g. MoveJ and MoveL). @@ -407,7 +364,7 @@ class RWSClient : public POCOClient * \throw std::out_of_range if argument is out of range. * \throw std::runtime_error if failed to create a string from the argument. */ - RWSResult setSpeedRatio(unsigned int ratio); + void setSpeedRatio(unsigned int ratio); /** * \brief A method for retrieving a file from the robot controller. @@ -416,37 +373,24 @@ class RWSClient : public POCOClient * * \param resource specifying the file's directory and name. * \param p_file_content for containing the retrieved file content. - * - * \return RWSResult containing the result. */ - RWSResult getFile(const FileResource& resource, std::string* p_file_content); + void getFile(const FileResource& resource, std::string* p_file_content); /** * \brief A method for uploading a file to the robot controller. * * \param resource specifying the file's directory and name. * \param file_content for the file's content. - * - * \return RWSResult containing the result. */ - RWSResult uploadFile(const FileResource& resource, const std::string& file_content); + void uploadFile(const FileResource& resource, const std::string& file_content); /** * \brief A method for deleting a file from the robot controller. * * \param resource specifying the file's directory and name. - * - * \return RWSResult containing the result. */ - RWSResult deleteFile(const FileResource& resource); + void deleteFile(const FileResource& resource); - - /** - * \brief A method for logging out the currently active RWS session. - * - * \return RWSResult containing the result. - */ - RWSResult logout(); /** * \brief A method for registering a user as local. @@ -454,10 +398,8 @@ class RWSClient : public POCOClient * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. - * - * \return RWSResult containing the result. */ - RWSResult registerLocalUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, + void registerLocalUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, const std::string& location = SystemConstants::General::EXTERNAL_LOCATION); @@ -467,10 +409,8 @@ class RWSClient : public POCOClient * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. - * - * \return RWSResult containing the result. */ - RWSResult registerRemoteUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, + void registerRemoteUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, const std::string& location = SystemConstants::General::EXTERNAL_LOCATION); @@ -480,25 +420,8 @@ class RWSClient : public POCOClient * \param result containing the result of the parsing. * \param poco_result containing the POCO result. */ - static void parseMessage(RWSResult* result, const POCOResult& poco_result); + static void parseMessage(RWSResult& result, const POCOResult& poco_result); - /** - * \brief Method for retrieving the internal log as a text string. - * - * \param verbose indicating if the log text should be verbose or not. - * - * \return std::string containing the log text. An empty text string is returned if the log is empty. - */ - std::string getLogText(const bool verbose = false) const; - - /** - * \brief Method for retrieving only the most recently logged event as a text string. - * - * \param verbose indicating if the log text should be verbose or not. - * - * \return std::string containing the log text. An empty text string is returned if the log is empty. - */ - std::string getLogTextLatestEvent(const bool verbose = false) const; private: /** @@ -531,14 +454,19 @@ class RWSClient : public POCOClient std::vector accepted_outcomes; }; + + /** + * \brief A method for logging out the currently active RWS session. + */ + void logout(); + /** * \brief Method for checking a communication result against the accepted outcomes. * - * \param result containing the result of the check. * \param poco_result containing the POCO result. * \param conditions containing the conditions for the evaluation. */ - void checkAcceptedOutcomes(RWSResult* result, const POCOResult& poco_result, const EvaluationConditions& conditions); + void checkAcceptedOutcomes(const POCOResult& poco_result, const EvaluationConditions& conditions); /** * \brief Method for evaluating the result from a POCO communication. diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 1e269ade..812f3ec9 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -518,30 +518,24 @@ class RWSInterface * * \param mechunit for the mechanical unit's name. * \param static_info for storing the retrieved information. - * - * \return bool indicating if the communication was successful or not (basic verification for non-empty data is made). */ - bool getMechanicalUnitStaticInfo(const std::string& mechunit, MechanicalUnitStaticInfo& static_info); + void getMechanicalUnitStaticInfo(const std::string& mechunit, MechanicalUnitStaticInfo& static_info); /** * \brief A method for retrieving dynamic information about a mechanical unit. * * \param mechunit for the mechanical unit's name. * \param dynamic_info for storing the retrieved information. - * - * \return bool indicating if the communication was successful or not (basic verification for non-empty data is made). */ - bool getMechanicalUnitDynamicInfo(const std::string& mechunit, MechanicalUnitDynamicInfo& dynamic_info); + void getMechanicalUnitDynamicInfo(const std::string& mechunit, MechanicalUnitDynamicInfo& dynamic_info); /** * \brief A method for retrieving the current jointtarget values of a mechanical unit. * * \param mechunit for the mechanical unit's name. * \param p_jointtarget for storing the retrieved jointtarget data. - * - * \return bool indicating if the communication was successful or not. Note: No checks are made for "correct parsing". */ - bool getMechanicalUnitJointTarget(const std::string& mechunit, JointTarget* p_jointtarget); + void getMechanicalUnitJointTarget(const std::string& mechunit, JointTarget* p_jointtarget); /** * \brief A method for retrieving the current robtarget values of a mechanical unit. @@ -551,10 +545,8 @@ class RWSInterface * \param coordinate for the coordinate mode (base, world, tool, or wobj) in which the robtarget will be reported. * \param tool for the tool frame relative to which the robtarget will be reported. * \param wobj for the work object (wobj) relative to which the robtarget will be reported. - * - * \return bool indicating if the communication was successful or not. Note: No checks are made for "correct parsing". */ - bool getMechanicalUnitRobTarget(const std::string& mechunit, + void getMechanicalUnitRobTarget(const std::string& mechunit, RobTarget* p_robtarget, Coordinate coordinate = Coordinate::ACTIVE, const std::string& tool = "", @@ -579,27 +571,23 @@ class RWSInterface * \param task for the name of the RAPID task containing the RAPID symbol. * \param module for the name of the RAPID module containing the RAPID symbol. * \param name for the name of the RAPID symbol. - * \param p_data for storing the retrieved RAPID symbol data. - * - * \return bool indicating if the communication was successful or not. Note: No checks are made for "correct parsing". + * \param data for storing the retrieved RAPID symbol data. */ - bool getRAPIDSymbolData(const std::string& task, + void getRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name, - RAPIDSymbolDataAbstract* p_data); + RAPIDSymbolDataAbstract& data); /** * \brief A method for retrieving the data of a RAPID symbol (parsed into a struct representing the RAPID data). * * \param task for the name of the RAPID task containing the RAPID symbol. * \param symbol indicating the RAPID symbol resource (name and module). - * \param p_data for storing the retrieved RAPID symbol data. - * - * \return bool indicating if the communication was successful or not. Note: No checks are made for "correct parsing". + * \param data for storing the retrieved RAPID symbol data. */ - bool getRAPIDSymbolData(const std::string& task, + void getRAPIDSymbolData(const std::string& task, const RAPIDSymbolResource& symbol, - RAPIDSymbolDataAbstract* p_data); + RAPIDSymbolDataAbstract& data); /** * \brief A method for retrieving information about the RAPID modules of a RAPID task defined in the robot controller. @@ -634,33 +622,31 @@ class RWSInterface /** * \brief A method for checking if the robot controller mode is in auto mode. * - * \return TriBool indicating if the mode is auto or not or unknown. + * \return if the mode is auto or not. */ - TriBool isAutoMode(); + bool isAutoMode(); /** * \brief A method for checking if the motors are on. * - * \return TriBool indicating if the motors are on or not or unknown. + * \return if the motors are on or not. */ - TriBool isMotorsOn(); + bool isMotorsOn(); /** * \brief A method for checking if RAPID is running. * - * \return TriBool indicating if RAPID is running or not or unknown. + * \return if RAPID is running or not. */ - TriBool isRAPIDRunning(); + bool isRAPIDRunning(); /** * \brief A method for setting the value of an IO signal. * * \param iosignal for the name of the IO signal. * \param value for the IO signal's new value. - * - * \return bool indicating if the communication was successful or not. */ - bool setIOSignal(const std::string& iosignal, const std::string& value); + void setIOSignal(const std::string& iosignal, const std::string& value); /** * \brief A method for setting the data of a RAPID symbol via raw text format. @@ -684,10 +670,8 @@ class RWSInterface * \param module name of the RAPID module containing the RAPID symbol. * \param name the name of the RAPID symbol. * \param data containing the RAPID symbol's new data. - * - * \return bool indicating if the communication was successful or not. */ - bool setRAPIDSymbolData(const std::string& task, + void setRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name, const std::string& data); @@ -699,10 +683,8 @@ class RWSInterface * \param module for the name of the RAPID module containing the RAPID symbol. * \param name for the name of the RAPID symbol. * \param data containing the RAPID symbol's new data. - * - * \return bool indicating if the communication was successful or not. */ - bool setRAPIDSymbolData(const std::string& task, + void setRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name, const RAPIDSymbolDataAbstract& data); @@ -713,47 +695,35 @@ class RWSInterface * \param task for the name of the RAPID task containing the RAPID symbol. * \param symbol indicating the RAPID symbol resource (name and module). * \param data containing the RAPID symbol's new data. - * - * \return bool indicating if the communication was successful or not. */ - bool setRAPIDSymbolData(const std::string& task, + void setRAPIDSymbolData(const std::string& task, const RAPIDSymbolResource& symbol, const RAPIDSymbolDataAbstract& data); /** * \brief A method for starting RAPID execution in the robot controller. - * - * \return bool indicating if the communication was successful or not. */ - bool startRAPIDExecution(); + void startRAPIDExecution(); /** * \brief A method for stopping RAPID execution in the robot controller. - * - * \return bool indicating if the communication was successful or not. */ - bool stopRAPIDExecution(); + void stopRAPIDExecution(); /** * \brief A method for reseting the RAPID program pointer in the robot controller. - * - * \return bool indicating if the communication was successful or not. */ - bool resetRAPIDProgramPointer(); + void resetRAPIDProgramPointer(); /** * \brief A method for turning on the robot controller's motors. - * - * \return bool indicating if the communication was successful or not. */ - bool setMotorsOn(); + void setMotorsOn(); /** * \brief A method for turning off the robot controller's motors. - * - * \return bool indicating if the communication was successful or not. */ - bool setMotorsOff(); + void setMotorsOff(); /** * \brief A method for setting the robot controller's speed ratio for RAPID motions (e.g. MoveJ and MoveL). @@ -761,10 +731,8 @@ class RWSInterface * Note: The ratio must be an integer in the range [0, 100] (ie: inclusive). * * \param ratio specifying the new ratio. - * - * \return bool indicating if the communication was successful or not. */ - bool setSpeedRatio(unsigned int ratio); + void setSpeedRatio(unsigned int ratio); /** * \brief A method for retrieving a file from the robot controller. @@ -773,29 +741,23 @@ class RWSInterface * * \param resource specifying the file's directory and name. * \param p_file_content for containing the retrieved file content. - * - * \return bool indicating if the communication was successful or not. */ - bool getFile(const FileResource& resource, std::string* p_file_content); + void getFile(const FileResource& resource, std::string* p_file_content); /** * \brief A method for uploading a file to the robot controller. * * \param resource specifying the file's directory and name. * \param file_content for the file's content. - * - * \return bool indicating if the communication was successful or not. */ - bool uploadFile(const FileResource& resource, const std::string& file_content); + void uploadFile(const FileResource& resource, const std::string& file_content); /** * \brief A method for deleting a file from the robot controller. * * \param resource specifying the file's directory and name. - * - * \return bool indicating if the communication was successful or not. */ - bool deleteFile(const FileResource& resource); + void deleteFile(const FileResource& resource); /** * \brief Creates a subscription group. @@ -814,10 +776,8 @@ class RWSInterface * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. - * - * \return bool indicating if the communication was successful or not. */ - bool registerLocalUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, + void registerLocalUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, const std::string& location = SystemConstants::General::EXTERNAL_LOCATION); @@ -827,10 +787,8 @@ class RWSInterface * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. - * - * \return bool indicating if the communication was successful or not. */ - bool registerRemoteUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, + void registerRemoteUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, const std::string& location = SystemConstants::General::EXTERNAL_LOCATION); @@ -870,9 +828,9 @@ class RWSInterface * \param attribute for specifying the XML node's required attribute. * \param compare_string for specifying the comparison string. * - * \return TriBool containing the result of the comparison. + * \return The result of the comparison. */ - TriBool compareSingleContent(const RWSResult& rws_result, + static bool compareSingleContent(const RWSResult& rws_result, const XMLAttribute& attribute, const std::string& compare_string); diff --git a/include/abb_librws/rws_poco_client.h b/include/abb_librws/rws_poco_client.h index fd6e5d6d..c2e52874 100644 --- a/include/abb_librws/rws_poco_client.h +++ b/include/abb_librws/rws_poco_client.h @@ -46,6 +46,8 @@ #include #include +#include +#include namespace abb { @@ -149,7 +151,114 @@ namespace rws Poco::Net::WebSocket webSocketConnect(const std::string& uri, const std::string& protocol); + /** + * \brief Method for retrieving the internal log as a text string. + * + * \param verbose indicating if the log text should be verbose or not. + * + * \return std::string containing the log text. An empty text string is returned if the log is empty. + */ + std::string getLogText(bool verbose = false) const; + + + /** + * \brief Method for retrieving only the most recently logged event as a text string. + * + * \param verbose indicating if the log text should be verbose or not. + * + * \return std::string containing the log text. An empty text string is returned if the log is empty. + */ + std::string getLogTextLatestEvent(bool verbose = false) const; + + private: + /** + * \brief A struct for containing HTTP info. + */ + struct HTTPInfo + { + /** + * \brief A struct for containing HTTP request info. + */ + struct RequestInfo + { + /** + * \brief Method used for the request. + */ + std::string method; + + /** + * \brief URI used for the request. + */ + std::string uri; + + /** + * \brief Content used for the request. + */ + std::string content; + }; + + /** + * \brief A struct for containing HTTP response info. + */ + struct ResponseInfo + { + /** + * \brief Response status. + */ + Poco::Net::HTTPResponse::HTTPStatus status; + + /** + * \brief Response header info. + */ + std::string header_info; + + /** + * \brief Response content. + */ + std::string content; + }; + + /** + * \brief Info about a HTTP request. + */ + std::optional request; + + /** + * \brief Info about a HTTP response. + */ + std::optional response; + + + /** + * \brief A method for adding info from a HTTP request. + * + * \param request for the HTTP request. + * \param request_content for the HTTP request's content. + */ + void addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, const std::string& request_content = ""); + + /** + * \brief A method for adding info from a HTTP response. + * + * \param response for the HTTP response. + * \param response_content for the HTTP response's content. + */ + void addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, const std::string& response_content = ""); + + + /** + * \brief A method to construct a text representation of the result. + * + * \param verbose indicating if the log text should be verbose or not. + * \param indent for indentation. + * + * \return std::string containing the text representation. + */ + std::string toString(bool verbose = false, size_t indent = 0) const; + }; + + /** * \brief A method for making a HTTP request. * @@ -166,28 +275,28 @@ namespace rws /** * \brief A method for sending and receiving HTTP messages. * - * \param result for the result. * \param request for the HTTP request. * \param response for the HTTP response. * \param request_content for the request's content. + * \param response_content for the response content. */ - void sendAndReceive(POCOResult& result, - Poco::Net::HTTPRequest& request, + void sendAndReceive(Poco::Net::HTTPRequest& request, Poco::Net::HTTPResponse& response, - const std::string& request_content); + const std::string& request_content, + std::string& response_content); /** * \brief A method for performing authentication. * - * \param result for the result. * \param request for the HTTP request. * \param response for the HTTP response. * \param request_content for the request's content. + * \param response_content for the response content. */ - void authenticate(POCOResult& result, - Poco::Net::HTTPRequest& request, + void authenticate(Poco::Net::HTTPRequest& request, Poco::Net::HTTPResponse& response, - const std::string& request_content); + const std::string& request_content, + std::string& response_content); /** * \brief A method for extracting and storing information from a cookie string. @@ -221,6 +330,16 @@ namespace rws * \brief A container for cookies received from a server. */ Poco::Net::NameValueCollection cookies_; + + /** + * \brief Static constant for the log's size. + */ + static const size_t LOG_SIZE = 20; + + /** + * \brief Container for logging communication results. + */ + std::deque log_; }; } // end namespace rws } // end namespace abb diff --git a/include/abb_librws/rws_poco_result.h b/include/abb_librws/rws_poco_result.h index 9123d285..77c2ad39 100644 --- a/include/abb_librws/rws_poco_result.h +++ b/include/abb_librws/rws_poco_result.h @@ -14,144 +14,47 @@ namespace abb :: rws struct POCOResult { /** - * \brief An enum for specifying a general status. + * \brief A constructor. + * + * \param http_status HTTP response status + * \param header_info HTTP response header info + * \param content HTTP response content */ - enum GeneralStatus - { - UNKNOWN, ///< Unknown status. - OK, ///< Ok status. - WEBSOCKET_NOT_ALLOCATED, ///< The WebSocket has not been allocated. - EXCEPTION_POCO_INVALID_ARGUMENT, ///< POCO invalid argument exception - EXCEPTION_POCO_TIMEOUT, ///< POCO timeout exception. - EXCEPTION_POCO_NET, ///< POCO net exception. - EXCEPTION_POCO_WEBSOCKET ///< POCO WebSocket exception. - }; + POCOResult(Poco::Net::HTTPResponse::HTTPStatus http_status, + Poco::Net::NameValueCollection const& header_info, std::string const& content); + + /** - * \brief A struct for containing POCO info. + * \brief Status of the HTTP response. */ - struct POCOInfo + Poco::Net::HTTPResponse::HTTPStatus httpStatus() const noexcept { - /** - * \brief A struct for containing HTTP info. - */ - struct HTTPInfo - { - /** - * \brief A struct for containing HTTP request info. - */ - struct RequestInfo - { - /** - * \brief Method used for the request. - */ - std::string method; - - /** - * \brief URI used for the request. - */ - std::string uri; - - /** - * \brief Content used for the request. - */ - std::string content; - }; - - /** - * \brief A struct for containing HTTP response info. - */ - struct ResponseInfo - { - /** - * \brief Response status. - */ - Poco::Net::HTTPResponse::HTTPStatus status; - - /** - * \brief Response header info. - */ - std::string header_info; - - /** - * \brief Response content. - */ - std::string content; - - /** - * \brief A default constructor. - */ - ResponseInfo() : status(Poco::Net::HTTPResponse::HTTP_OK) {} - }; - - /** - * \brief Info about a HTTP request. - */ - RequestInfo request; - - /** - * \brief Info about a HTTP response. - */ - ResponseInfo response; - }; - - /** - * \brief Container for HTTP info. - */ - HTTPInfo http; - }; - - /** - * \brief Container for a general status. - */ - GeneralStatus status; + return httpStatus_; + } - /** - * \brief Container for an exception message (if one occurred). - */ - std::string exception_message; /** - * \brief Container for POCO info. + * \brief HTTP response header info. */ - POCOInfo poco_info; + auto const& headerInfo() const noexcept + { + return headerInfo_; + } - /** - * \brief A default constructor. - */ - POCOResult() : status(UNKNOWN) {}; /** - * \brief A method for adding info from a HTTP request. - * - * \param request for the HTTP request. - * \param request_content for the HTTP request's content. + * \brief Content of the HTTP response. */ - void addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, const std::string& request_content = ""); - - /** - * \brief A method for adding info from a HTTP response. - * - * \param response for the HTTP response. - * \param response_content for the HTTP response's content. - */ - void addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, const std::string& response_content = ""); + std::string const& content() const noexcept + { + return content_; + } - /** - * \brief A method to map the general status to a std::string. - * - * \return std::string containing the mapped general status. - */ - std::string mapGeneralStatus() const; - /** - * \brief A method to construct a text representation of the result. - * - * \param verbose indicating if the log text should be verbose or not. - * \param indent for indentation. - * - * \return std::string containing the text representation. - */ - std::string toString(const bool verbose = false, const size_t indent = 0) const; + private: + Poco::Net::HTTPResponse::HTTPStatus httpStatus_; + std::vector> headerInfo_; + std::string content_; }; } \ No newline at end of file diff --git a/include/abb_librws/rws_state_machine_interface.h b/include/abb_librws/rws_state_machine_interface.h index 9279b0de..246682e0 100644 --- a/include/abb_librws/rws_state_machine_interface.h +++ b/include/abb_librws/rws_state_machine_interface.h @@ -894,55 +894,41 @@ class RWSStateMachineInterface : public RWSInterface * * \param task specifying the RAPID task. * \param p_settings for storing the retrieved data. - * - * \return bool indicating if the communication was successful or not. */ - bool getSettings(const std::string& task, EGMSettings* p_settings) const; + void getSettings(const std::string& task, EGMSettings* p_settings) const; /** * \brief Set the settings for the EGM RAPID instructions. * * \param task specifying the RAPID task. * \param settings containing the new data. - * - * \return bool indicating if the communication was successful or not. */ - bool setSettings(const std::string& task, const EGMSettings& settings) const; + void setSettings(const std::string& task, const EGMSettings& settings) const; /** * \brief Signal the StateMachine AddIn to start EGM joint motions. - * - * \return bool indicating if the signaling was successful or not. */ - bool signalEGMStartJoint() const; + void signalEGMStartJoint() const; /** * \brief Signal the StateMachine AddIn to start EGM pose motions. - * - * \return bool indicating if the signaling was successful or not. */ - bool signalEGMStartPose() const; + void signalEGMStartPose() const; /** * \brief Signal the StateMachine AddIn to start EGM position streaming. - * - * \return bool indicating if the signaling was successful or not. */ - bool signalEGMStartStream() const; + void signalEGMStartStream() const; /** * \brief Signal the StateMachine AddIn to stop any current EGM motions. - * - * \return bool indicating if the signaling was successful or not. */ - bool signalEGMStop() const; + void signalEGMStop() const; /** * \brief Signal the StateMachine AddIn to stop any current position streaming. - * - * \return bool indicating if the signaling was successful or not. */ - bool signalEGMStopStream() const; + void signalEGMStopStream() const; private: /** @@ -978,18 +964,18 @@ class RWSStateMachineInterface : public RWSInterface * * \param task specifying the RAPID task. * - * \return TriBool indicating if the state is idle or not. + * \return if the state is idle or not. */ - TriBool isStateIdle(const std::string& task) const; + bool isStateIdle(const std::string& task) const; /** * \brief Checks if a mechanical unit is stationary or not. * * \param mechanical_unit specifying the mechanical unit to check. * - * \return TriBool indicating if the mechanical unit is stationary or not. + * \return if the mechanical unit is stationary or not. */ - TriBool isStationary(const std::string& mechanical_unit) const; + bool isStationary(const std::string& mechanical_unit) const; private: /** @@ -1017,10 +1003,8 @@ class RWSStateMachineInterface : public RWSInterface * \param task specifying the RAPID task. * \param routine_name specifying routine name. * \param routine_number specifying routine number. - * - * \return bool indicating if the communication was successful or not. */ - bool runCallByVar(const std::string& task, + void runCallByVar(const std::string& task, const std::string& routine_name, const unsigned int routine_number) const; @@ -1029,76 +1013,62 @@ class RWSStateMachineInterface : public RWSInterface * * \param task specifying the RAPID task. * \param file_path specifying file path to the module. - * - * \return bool indicating if the communication was successful or not. */ - bool runModuleLoad(const std::string& task, const std::string& file_path) const; + void runModuleLoad(const std::string& task, const std::string& file_path) const; /** * \brief Request the execution of the predefined RAPID procedure "runModuleUnload". * * \param task specifying the RAPID task. * \param file_path specifying file path to the module. - * - * \return bool indicating if the communication was successful or not. */ - bool runModuleUnload(const std::string& task, const std::string& file_path) const; + void runModuleUnload(const std::string& task, const std::string& file_path) const; /** * \brief Request the execution of the predefined RAPID procedure "runMoveAbsJ". * * \param task specifying the RAPID task. * \param joint_target specifying jointtarget goal. - * - * \return bool indicating if the communication was successful or not. */ - bool runMoveAbsJ(const std::string& task, const JointTarget& joint_target) const; + void runMoveAbsJ(const std::string& task, const JointTarget& joint_target) const; /** * \brief Request the execution of the predefined RAPID procedure "runMoveJ". * * \param task specifying the RAPID task. * \param rob_target specifying the robtarget goal. - * - * \return bool indicating if the communication was successful or not. */ - bool runMoveJ(const std::string& task, const RobTarget& rob_target) const; + void runMoveJ(const std::string& task, const RobTarget& rob_target) const; /** * \brief Request the execution of the predefined RAPID procedure "runMoveToCalibrationPosition". * * \param task specifying the RAPID task. - * - * \return bool indicating if the communication was successful or not. */ - bool runMoveToCalibrationPosition(const std::string& task) const; + void runMoveToCalibrationPosition(const std::string& task) const; /** * \brief Set the move speed for the predefined RAPID procedures "runMoveAbsJ" and "runMoveJ". * * \param task specifying the RAPID task. * \param speed_data containing the new data. - * - * \return bool indicating if the communication was successful or not. */ - bool setMoveSpeed(const std::string& task, const SpeedData& speed_data) const; + void setMoveSpeed(const std::string& task, const SpeedData& speed_data) const; /** * \brief Set the routine name specifying which routine to run. * * \param task specifying the RAPID task. * \param routine_name containing the new data. - * - * \return bool indicating if the communication was successful or not. */ - bool setRoutineName(const std::string& task, const std::string& routine_name) const; + void setRoutineName(const std::string& task, const std::string& routine_name) const; /** * \brief Signal the StateMachine AddIn to run RAPID routine(s). * - * \return bool indicating if the signaling was successful or not. + * \return void indicating if the signaling was successful or not. */ - bool signalRunRAPIDRoutine() const; + void signalRunRAPIDRoutine() const; private: /** @@ -1124,346 +1094,256 @@ class RWSStateMachineInterface : public RWSInterface /** * \brief Request turning off both SmartGrippers' first blow. - * - * \return bool indicating if the communication was successful or not. */ - bool dualBlow1Off() const; + void dualBlow1Off() const; /** * \brief Request turning on both SmartGrippers' first blow. - * - * \return bool indicating if the communication was successful or not. */ - bool dualBlow1On() const; + void dualBlow1On() const; /** * \brief Request turning off both SmartGrippers' second blow. - * - * \return bool indicating if the communication was successful or not. */ - bool dualBlow2Off() const; + void dualBlow2Off() const; /** * \brief Request turning on both SmartGrippers' second blow. - * - * \return bool indicating if the communication was successful or not. */ - bool dualBlow2On() const; + void dualBlow2On() const; /** * \brief Request calibration of both SmartGrippers. - * - * \return bool indicating if the communication was successful or not. */ - bool dualCalibrate() const; + void dualCalibrate() const; /** * \brief Get the settings for both SmartGrippers' RAPID instructions. * * \param p_left_settings for storing the retrieved data for the left gripper. * \param p_right_settings for storing the retrieved data for the right gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool dualGetSettings(SGSettings* p_left_settings, SGSettings* p_right_settings) const; + void dualGetSettings(SGSettings* p_left_settings, SGSettings* p_right_settings) const; /** * \brief Request inwards grip of both SmartGrippers. - * - * \return bool indicating if the communication was successful or not. */ - bool dualGripIn() const; + void dualGripIn() const; /** * \brief Request outwards grip of both SmartGrippers. - * - * \return bool indicating if the communication was successful or not. */ - bool dualGripOut() const; + void dualGripOut() const; /** * \brief Request initialization of both SmartGrippers. - * - * \return bool indicating if the communication was successful or not. */ - bool dualInitialize() const; + void dualInitialize() const; /** * \brief Request move of both SmartGrippers. * * \param left_position specifying targeted position [mm] for the left gripper. * \param right_position specifying targeted position [mm] for the right gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool dualMoveTo(const float left_position, const float right_position) const; + void dualMoveTo(const float left_position, const float right_position) const; /** * \brief Set the settings for both SmartGrippers' instructions. * * \param left_settings containing the new data for the left gripper. * \param right_settings containing the new data for the right gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool dualSetSettings(const SGSettings& left_settings, const SGSettings& right_settings) const; + void dualSetSettings(const SGSettings& left_settings, const SGSettings& right_settings) const; /** * \brief Request turning off both SmartGrippers' first vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool dualVacuum1Off() const; + void dualVacuum1Off() const; /** * \brief Request turning on both SmartGrippers' first vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool dualVacuum1On() const; + void dualVacuum1On() const; /** * \brief Request turning off both SmartGrippers' second vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool dualVacuum2Off() const; + void dualVacuum2Off() const; /** * \brief Request turning on both SmartGrippers' second vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool dualVacuum2On() const; + void dualVacuum2On() const; /** * \brief Request turning off the left SmartGripper's first blow. - * - * \return bool indicating if the communication was successful or not. */ - bool leftBlow1Off() const; + void leftBlow1Off() const; /** * \brief Request turning on the left SmartGripper's first blow. - * - * \return bool indicating if the communication was successful or not. */ - bool leftBlow1On() const; + void leftBlow1On() const; /** * \brief Request turning off the left SmartGripper's second blow. - * - * \return bool indicating if the communication was successful or not. */ - bool leftBlow2Off() const; + void leftBlow2Off() const; /** * \brief Request turning on the left SmartGripper's second blow. - * - * \return bool indicating if the communication was successful or not. */ - bool leftBlow2On() const; + void leftBlow2On() const; /** * \brief Request calibration of the left SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool leftCalibrate() const; + void leftCalibrate() const; /** * \brief Get the settings for the left SmartGripper's RAPID instructions. * * \param p_settings for storing the retrieved data for the left gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool leftGetSettings(SGSettings* p_settings) const; + void leftGetSettings(SGSettings* p_settings) const; /** * \brief Request inwards grip of the left SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool leftGripIn() const; + void leftGripIn() const; /** * \brief Request outwards grip of the left SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool leftGripOut() const; + void leftGripOut() const; /** * \brief Request initialization of the left SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool leftInitialize() const; + void leftInitialize() const; /** * \brief Request move of the left SmartGripper. * * \param position specifying targeted position [mm] for the left gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool leftMoveTo(const float position) const; + void leftMoveTo(const float position) const; /** * \brief Set the settings for the left SmartGripper's instructions. * * \param settings containing the new data for the left gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool leftSetSettings(const SGSettings& settings) const; + void leftSetSettings(const SGSettings& settings) const; /** * \brief Request turning off the left SmartGripper's first vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool leftVacuum1Off() const; + void leftVacuum1Off() const; /** * \brief Request turning on the left SmartGripper's first vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool leftVacuum1On() const; + void leftVacuum1On() const; /** * \brief Request turning off the left SmartGripper's second vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool leftVacuum2Off() const; + void leftVacuum2Off() const; /** * \brief Request turning on the left SmartGripper's second vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool leftVacuum2On() const; + void leftVacuum2On() const; /** * \brief Request turning off the right SmartGripper's first blow. - * - * \return bool indicating if the communication was successful or not. */ - bool rightBlow1Off() const; + void rightBlow1Off() const; /** * \brief Request turning on the right SmartGripper's first blow. - * - * \return bool indicating if the communication was successful or not. */ - bool rightBlow1On() const; + void rightBlow1On() const; /** * \brief Request turning off the right SmartGripper's second blow. - * - * \return bool indicating if the communication was successful or not. */ - bool rightBlow2Off() const; + void rightBlow2Off() const; /** * \brief Request turning on the right SmartGripper's second blow. - * - * \return bool indicating if the communication was successful or not. */ - bool rightBlow2On() const; + void rightBlow2On() const; /** * \brief Request calibration of the right SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool rightCalibrate() const; + void rightCalibrate() const; /** * \brief Get the settings for the right SmartGripper's RAPID instructions. * * \param p_settings for storing the retrieved data for the right gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool rightGetSettings(SGSettings* p_settings) const; + void rightGetSettings(SGSettings* p_settings) const; /** * \brief Request inwards grip of the right SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool rightGripIn() const; + void rightGripIn() const; /** * \brief Request outwards grip of the right SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool rightGripOut() const; + void rightGripOut() const; /** * \brief Request initialization of the right SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool rightInitialize() const; + void rightInitialize() const; /** * \brief Request move of the right SmartGripper. * * \param position specifying targeted position [mm] for the right gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool rightMoveTo(const float position) const; + void rightMoveTo(const float position) const; /** * \brief Set the settings for the right SmartGripper's instructions. * * \param settings containing the new data for the right gripper. - * - * \return bool indicating if the communication was successful or not. */ - bool rightSetSettings(const SGSettings& settings) const; + void rightSetSettings(const SGSettings& settings) const; /** * \brief Request turning off the right SmartGripper's first vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool rightVacuum1Off() const; + void rightVacuum1Off() const; /** * \brief Request turning on the right SmartGripper's first vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool rightVacuum1On() const; + void rightVacuum1On() const; /** * \brief Request turning off the right SmartGripper's second vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool rightVacuum2Off() const; + void rightVacuum2Off() const; /** * \brief Request turning on the right SmartGripper's second vacuum. - * - * \return bool indicating if the communication was successful or not. */ - bool rightVacuum2On() const; + void rightVacuum2On() const; /** * \brief Signal the StateMachine to run SmartGripper routine(s). * - * \return bool indicating if the signaling was successful or not. + * \return void indicating if the signaling was successful or not. */ - bool signalRunSGRoutine() const; + void signalRunSGRoutine() const; private: /** @@ -1471,40 +1351,32 @@ class RWSStateMachineInterface : public RWSInterface * * \param task specifying the RAPID task. * \param p_settings for storing the retrieved data. - * - * \return bool indicating if the communication was successful or not. */ - bool getSettings(const std::string& task, SGSettings* p_settings) const; + void getSettings(const std::string& task, SGSettings* p_settings) const; /** * \brief Set command input for specifying a SmartGripper's desired command. * * \param task specifying the RAPID task. * \param command specifying the desired command. - * - * \return bool indicating if the communication was successful or not. */ - bool setCommandInput(const std::string& task, const SGCommands& command) const; + void setCommandInput(const std::string& task, const SGCommands& command) const; /** * \brief Set the settings for a SmartGripper's RAPID instructions. * * \param task specifying the RAPID task. * \param settings specifying the settings. - * - * \return bool indicating if the communication was successful or not. */ - bool setSettings(const std::string& task, const SGSettings& settings) const; + void setSettings(const std::string& task, const SGSettings& settings) const; /** * \brief Set target position input for specifying where to move a SmartGripper. * * \param task specifying the RAPID task. * \param position specifying targeted position [mm] for a SmartGripper. - * - * \return bool indicating if the communication was successful or not. */ - bool setTargetPositionInput(const std::string& task, const float position) const; + void setTargetPositionInput(const std::string& task, const float position) const; /** * \brief The RWS interface instance. @@ -1530,20 +1402,16 @@ class RWSStateMachineInterface : public RWSInterface * * \param task specifying the RAPID task. * \param p_base_frame for storing the retrieved data. - * - * \return bool indicating if the communication was successful or not. */ - bool getBaseFrame(const std::string& task, Pose* p_base_frame) const; + void getBaseFrame(const std::string& task, Pose* p_base_frame) const; /** * \brief Get a motion task's calibration target, extracted during initialization of the task. * * \param task specifying the RAPID task. * \param p_calibration_joint_target for storing the retrieved data. - * - * \return bool indicating if the communication was successful or not. */ - bool getCalibrationTarget(const std::string& task, JointTarget* p_calibration_joint_target) const; + void getCalibrationTarget(const std::string& task, JointTarget* p_calibration_joint_target) const; private: /** @@ -1570,32 +1438,28 @@ class RWSStateMachineInterface : public RWSInterface * * \param task specifying the RAPID task. * - * \return TriBool indicating if the watchdog is active or not. + * \return indicating if the watchdog is active or not. */ - TriBool isActive(const std::string& task) const; + bool isActive(const std::string& task) const; /** * \brief Checks if the watchdog is set to watch an external status signal or not. * * \param task specifying the RAPID task. * - * \return TriBool indicating if the watchdog is set to watch an external status signal or not. + * \return indicating if the watchdog is set to watch an external status signal or not. */ - TriBool isCheckingExternalStatus(const std::string& task) const; + bool isCheckingExternalStatus(const std::string& task) const; /** * \brief Set the external status signal, which the watchdog can watch. - * - * \return bool indicating if the communication was successful or not. */ - bool setExternalStatusSignal() const; + void setExternalStatusSignal() const; /** * \brief Signal the watchdog to stop the StateMachine. - * - * \return bool indicating if the signaling was successful or not. */ - bool signalStopRequest() const; + void signalStopRequest() const; private: /** @@ -1639,10 +1503,8 @@ class RWSStateMachineInterface : public RWSInterface * \brief Toggles an IO signal. * * \param iosignal specifying the IO signal to toggle. - * - * \return bool indicating if the toggling was successful or not. */ - bool toggleIOSignal(const std::string& iosignal); + void toggleIOSignal(const std::string& iosignal); /** * \brief Services provided by the StateMachine AddIn. diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 3a11c815..92e2d0a7 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -41,6 +41,8 @@ #include +#include + namespace { @@ -68,6 +70,21 @@ typedef SystemConstants::RWS::XMLAttributes XMLAttributes; * Primary methods */ + +RWSClient::~RWSClient() +{ + try + { + logout(); + } + catch (std::exception const& e) + { + // Catch all exceptions in dtor. + std::cerr << "Exception in RWSClient::~RWSClient(): " << e.what() << std::endl; + } +} + + RWSResult RWSClient::getContollerService() { std::string uri = Services::CTRL; @@ -278,42 +295,30 @@ RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource) return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSResult RWSClient::getRAPIDSymbolData(const RAPIDResource& resource, RAPIDSymbolDataAbstract* p_data) +void RWSClient::getRAPIDSymbolData(const RAPIDResource& resource, RAPIDSymbolDataAbstract& data) { RWSResult result; std::string data_type; - if (p_data) + RWSResult const temp_result = getRAPIDSymbolProperties(resource); + + data_type = xmlFindTextContent(temp_result, XMLAttributes::CLASS_DATTYP); + + if (data.getType().compare(data_type) == 0) { - RWSResult temp_result = getRAPIDSymbolProperties(resource); + result = getRAPIDSymbolData(resource); - if (temp_result.success) + std::string value = xmlFindTextContent(result, XMLAttributes::CLASS_VALUE); + + if (!value.empty()) { - data_type = xmlFindTextContent(temp_result.p_xml_document, XMLAttributes::CLASS_DATTYP); - - if (p_data->getType().compare(data_type) == 0) - { - result = getRAPIDSymbolData(resource); - - if (result.success) - { - std::string value = xmlFindTextContent(result.p_xml_document, XMLAttributes::CLASS_VALUE); - - if (!value.empty()) - { - p_data->parseString(value); - } - else - { - result.success = false; - result.error_message = "getRAPIDSymbolData(...): RAPID value string was empty"; - } - } - } + data.parseString(value); + } + else + { + throw std::logic_error("getRAPIDSymbolData(...): RAPID value string was empty"); } } - - return result; } RWSResult RWSClient::getRAPIDSymbolProperties(const RAPIDResource& resource) @@ -327,7 +332,7 @@ RWSResult RWSClient::getRAPIDSymbolProperties(const RAPIDResource& resource) return evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSResult RWSClient::setIOSignal(const std::string& iosignal, const std::string& value) +void RWSClient::setIOSignal(const std::string& iosignal, const std::string& value) { std::string uri = generateIOSignalPath(iosignal) + "?" + Queries::ACTION_SET; std::string content = Identifiers::LVALUE + "=" + value; @@ -336,10 +341,10 @@ RWSResult RWSClient::setIOSignal(const std::string& iosignal, const std::string& evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const std::string& data) +void RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const std::string& data) { std::string uri = generateRAPIDDataPath(resource) + "?" + Queries::ACTION_SET; std::string content = Identifiers::VALUE + "=" + data; @@ -348,15 +353,15 @@ RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const std evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const RAPIDSymbolDataAbstract& data) +void RWSClient::setRAPIDSymbolData(const RAPIDResource& resource, const RAPIDSymbolDataAbstract& data) { - return setRAPIDSymbolData(resource, data.constructString()); + setRAPIDSymbolData(resource, data.constructString()); } -RWSResult RWSClient::startRAPIDExecution() +void RWSClient::startRAPIDExecution() { std::string uri = Resources::RW_RAPID_EXECUTION + "?" + Queries::ACTION_START; std::string content = "regain=continue&execmode=continue&cycle=forever&condition=none&stopatbp=disabled&alltaskbytsp=false"; @@ -365,10 +370,10 @@ RWSResult RWSClient::startRAPIDExecution() evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::stopRAPIDExecution() +void RWSClient::stopRAPIDExecution() { std::string uri = Resources::RW_RAPID_EXECUTION + "?" + Queries::ACTION_STOP; std::string content = "stopmode=stop"; @@ -377,10 +382,10 @@ RWSResult RWSClient::stopRAPIDExecution() evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::resetRAPIDProgramPointer() +void RWSClient::resetRAPIDProgramPointer() { std::string uri = Resources::RW_RAPID_EXECUTION + "?" + Queries::ACTION_RESETPP; @@ -388,10 +393,10 @@ RWSResult RWSClient::resetRAPIDProgramPointer() evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri), evaluation_conditions); + evaluatePOCOResult(httpPost(uri), evaluation_conditions); } -RWSResult RWSClient::setMotorsOn() +void RWSClient::setMotorsOn() { std::string uri = Resources::RW_PANEL_CTRLSTATE + "?" + Queries::ACTION_SETCTRLSTATE; std::string content = "ctrl-state=motoron"; @@ -400,10 +405,10 @@ RWSResult RWSClient::setMotorsOn() evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::setMotorsOff() +void RWSClient::setMotorsOff() { std::string uri = Resources::RW_PANEL_CTRLSTATE + "?" + Queries::ACTION_SETCTRLSTATE; std::string content = "ctrl-state=motoroff"; @@ -412,10 +417,10 @@ RWSResult RWSClient::setMotorsOff() evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::setSpeedRatio(unsigned int ratio) +void RWSClient::setSpeedRatio(unsigned int ratio) { if(ratio > 100) throw std::out_of_range("Speed ratio argument out of range (should be 0 <= ratio <= 100)"); @@ -430,35 +435,26 @@ RWSResult RWSClient::setSpeedRatio(unsigned int ratio) evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::getFile(const FileResource& resource, std::string* p_file_content) +void RWSClient::getFile(const FileResource& resource, std::string* p_file_content) { - RWSResult rws_result; - POCOResult poco_result; - if (p_file_content) { std::string uri = generateFilePath(resource); - poco_result = httpGet(uri); + POCOResult const poco_result = httpGet(uri); EvaluationConditions evaluation_conditions; evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); - rws_result = evaluatePOCOResult(poco_result, evaluation_conditions); - - if (rws_result.success) - { - *p_file_content = poco_result.poco_info.http.response.content; - } + evaluatePOCOResult(poco_result, evaluation_conditions); + *p_file_content = poco_result.content(); } - - return rws_result; } -RWSResult RWSClient::uploadFile(const FileResource& resource, const std::string& file_content) +void RWSClient::uploadFile(const FileResource& resource, const std::string& file_content) { std::string uri = generateFilePath(resource); std::string content = file_content; @@ -468,10 +464,10 @@ RWSResult RWSClient::uploadFile(const FileResource& resource, const std::string& evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_CREATED); - return evaluatePOCOResult(httpPut(uri, content), evaluation_conditions); + evaluatePOCOResult(httpPut(uri, content), evaluation_conditions); } -RWSResult RWSClient::deleteFile(const FileResource& resource) +void RWSClient::deleteFile(const FileResource& resource) { std::string uri = generateFilePath(resource); @@ -480,23 +476,23 @@ RWSResult RWSClient::deleteFile(const FileResource& resource) evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); - return evaluatePOCOResult(httpDelete(uri), evaluation_conditions); + evaluatePOCOResult(httpDelete(uri), evaluation_conditions); } -RWSResult RWSClient::logout() +void RWSClient::logout() { std::string uri = Resources::LOGOUT; EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = true; + evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); - return evaluatePOCOResult(httpGet(uri), evaluation_conditions); + evaluatePOCOResult(httpGet(uri), evaluation_conditions); } -RWSResult RWSClient::registerLocalUser(const std::string& username, +void RWSClient::registerLocalUser(const std::string& username, const std::string& application, const std::string& location) { @@ -511,12 +507,10 @@ RWSResult RWSClient::registerLocalUser(const std::string& username, evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_CREATED); - RWSResult result = evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); - - return result; + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSResult RWSClient::registerRemoteUser(const std::string& username, +void RWSClient::registerRemoteUser(const std::string& username, const std::string& application, const std::string& location) { @@ -531,9 +525,7 @@ RWSResult RWSClient::registerRemoteUser(const std::string& username, evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_CREATED); - RWSResult result = evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); - - return result; + evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } /************************************************************ @@ -545,106 +537,43 @@ RWSResult RWSClient::evaluatePOCOResult(const POCOResult& poco_result, { RWSResult result; - checkAcceptedOutcomes(&result, poco_result, conditions); - - if (poco_result.status != POCOResult::OK) - { - result.success = false; - result.error_message = poco_result.exception_message; - } - - if (result.success && conditions.parse_message_into_xml) - { - parseMessage(&result, poco_result); - } + checkAcceptedOutcomes(poco_result, conditions); - if (log_.size() >= LOG_SIZE) + if (conditions.parse_message_into_xml) { - log_.pop_back(); + parseMessage(result, poco_result); } - log_.push_front(poco_result); return result; } -void RWSClient::checkAcceptedOutcomes(RWSResult* result, - const POCOResult& poco_result, +void RWSClient::checkAcceptedOutcomes(const POCOResult& poco_result, const EvaluationConditions& conditions) { - if (result) + if (std::find(conditions.accepted_outcomes.begin(), conditions.accepted_outcomes.end(), poco_result.httpStatus()) == conditions.accepted_outcomes.end()) { - if (poco_result.status == POCOResult::OK && poco_result.exception_message.empty()) - { - for (size_t i = 0; i < conditions.accepted_outcomes.size() && !result->success; ++i) - { - result->success = (poco_result.poco_info.http.response.status == conditions.accepted_outcomes.at(i)); - } - - if (!result->success) - { - result->error_message = "checkAcceptedOutcomes(...): RWS response status not accepted"; - } - } + throw std::runtime_error("checkAcceptedOutcomes(...): RWS response status " + std::to_string(poco_result.httpStatus()) + " not accepted"); } } -void RWSClient::parseMessage(RWSResult* result, const POCOResult& poco_result) +void RWSClient::parseMessage(RWSResult& result, const POCOResult& poco_result) { - if (result) - { - std::stringstream ss; - - if (!poco_result.poco_info.http.response.content.empty()) - { - ss << poco_result.poco_info.http.response.content; - } - else - { - // XML parsing: Missing message - result->success = false; - result->error_message = "parseMessage(...): RWS response was empty"; - } - - if (result->success) - { - try - { - Poco::XML::InputSource input_source(ss); - result->p_xml_document = Poco::XML::DOMParser().parse(&input_source); - } - catch (...) - { - // XML parsing: Failed - result->success = false; - result->error_message = "parseMessage(...): XML parser failed to parse RWS response"; - } - } - } -} + std::stringstream ss; -std::string RWSClient::getLogText(bool verbose) const -{ - if (log_.size() == 0) + if (!poco_result.content().empty()) { - return ""; + ss << poco_result.content(); } - - std::stringstream ss; - - for (size_t i = 0; i < log_.size(); ++i) + else { - std::stringstream temp; - temp << i + 1 << ". "; - ss << temp.str() << log_[i].toString(verbose, temp.str().size()) << std::endl; + // XML parsing: Missing message + throw std::logic_error("parseMessage(...): RWS response was empty"); } - return ss.str(); + Poco::XML::InputSource input_source(ss); + result = Poco::XML::DOMParser().parse(&input_source); } -std::string RWSClient::getLogTextLatestEvent(bool verbose) const -{ - return (log_.size() == 0 ? "" : log_[0].toString(verbose, 0)); -} std::string RWSClient::generateConfigurationPath(const std::string& topic, const std::string& type) { diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index 2229299e..7ca1187c 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -94,10 +94,9 @@ std::vector RWSInterface::getCFGArms() std::vector result; RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::ARM); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -138,10 +137,9 @@ std::vector RWSInterface::getCFGJoints() std::vector result; RWSResult rws_result = rws_client_.getConfigurationInstances("MOC", "JOINT"); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -191,12 +189,10 @@ std::vector RWSInterface::getCFGMechanicalUnits() { std::vector result; - RWSResult rws_result; - rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::MECHANICAL_UNIT); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); + RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::MECHANICAL_UNIT); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -239,12 +235,10 @@ std::vector RWSInterface::getCFGMechanicalUnitGro { std::vector result; - RWSResult rws_result; - rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::MECHANICAL_UNIT_GROUP); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); + RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::MECHANICAL_UNIT_GROUP); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -287,12 +281,10 @@ std::vector RWSInterface::getCFGPresentOptions() { std::vector result; - RWSResult rws_result; - rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::PRESENT_OPTIONS); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); + RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::PRESENT_OPTIONS); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -326,10 +318,9 @@ std::vector RWSInterface::getCFGRobots() std::vector result; RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::ROBOT); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -424,10 +415,9 @@ std::vector RWSInterface::getCFGSingles() std::vector result; RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::MOC, Identifiers::SINGLE); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -517,10 +507,9 @@ std::vector RWSInterface::getCFGTransmission() std::vector result; RWSResult rws_result = rws_client_.getConfigurationInstances("MOC", "TRANSMISSION"); - if(!rws_result.success) throw std::runtime_error(EXCEPTION_GET_CFG); std::vector instances; - instances = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); + instances = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_DT_INSTANCE_LI); for(size_t i = 0; i < instances.size(); ++i) { @@ -555,7 +544,7 @@ std::vector RWSInterface::getPresentRobotWareOptions() RWSResult rws_result = rws_client_.getConfigurationInstances(Identifiers::SYS, Identifiers::PRESENT_OPTIONS); - std::vector node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_CFG_IA_T_LI); + std::vector node_list = xmlFindNodes(rws_result, XMLAttributes::CLASS_CFG_IA_T_LI); for (size_t i = 0; i < node_list.size(); i+=2) { @@ -569,266 +558,239 @@ std::vector RWSInterface::getPresentRobotWareOptions() return result; } + std::string RWSInterface::getIOSignal(const std::string& iosignal) { - std::string result; - RWSResult rws_result = rws_client_.getIOSignal(iosignal); - - if (rws_result.success) - { - result = xmlFindTextContent(rws_result.p_xml_document, XMLAttributes::CLASS_LVALUE); - } - - return result; + return xmlFindTextContent(rws_result, XMLAttributes::CLASS_LVALUE); } -bool RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, MechanicalUnitStaticInfo& static_info) -{ - bool result = false; +void RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, MechanicalUnitStaticInfo& static_info) +{ RWSResult rws_result = rws_client_.getMechanicalUnitStaticInfo(mechunit); - if(rws_result.success) - { - static_info.task_name = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "task-name")); - static_info.is_integrated_unit = xmlFindTextContent(rws_result.p_xml_document, - XMLAttribute("class", "is-integrated-unit")); - static_info.has_integrated_unit = xmlFindTextContent(rws_result.p_xml_document, - XMLAttribute("class", "has-integrated-unit")); - std::string type = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "type")); + static_info.task_name = xmlFindTextContent(rws_result, XMLAttribute("class", "task-name")); + static_info.is_integrated_unit = xmlFindTextContent(rws_result, + XMLAttribute("class", "is-integrated-unit")); + static_info.has_integrated_unit = xmlFindTextContent(rws_result, + XMLAttribute("class", "has-integrated-unit")); + std::string type = xmlFindTextContent(rws_result, XMLAttribute("class", "type")); - // Assume mechanical unit type is undefined, update based on contents of 'type'. - static_info.type = MechanicalUnitType::UNDEFINED; + // Assume mechanical unit type is undefined, update based on contents of 'type'. + static_info.type = MechanicalUnitType::UNDEFINED; - if(type == "None") - { - static_info.type = MechanicalUnitType::NONE; - } - else if(type == "TCPRobot") - { - static_info.type = MechanicalUnitType::TCP_ROBOT; - } - else if(type == "Robot") - { - static_info.type = MechanicalUnitType::ROBOT; - } - else if(type == "Single") - { - static_info.type = MechanicalUnitType::SINGLE; - } + if(type == "None") + { + static_info.type = MechanicalUnitType::NONE; + } + else if(type == "TCPRobot") + { + static_info.type = MechanicalUnitType::TCP_ROBOT; + } + else if(type == "Robot") + { + static_info.type = MechanicalUnitType::ROBOT; + } + else if(type == "Single") + { + static_info.type = MechanicalUnitType::SINGLE; + } - std::stringstream axes(xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "axes"))); - axes >> static_info.axes; + std::stringstream axes(xmlFindTextContent(rws_result, XMLAttribute("class", "axes"))); + axes >> static_info.axes; - std::stringstream axes_total(xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "axes-total"))); - axes_total >> static_info.axes_total; + std::stringstream axes_total(xmlFindTextContent(rws_result, XMLAttribute("class", "axes-total"))); + axes_total >> static_info.axes_total; - // Basic verification. - if(!static_info.task_name.empty() && - !static_info.is_integrated_unit.empty() && - !static_info.has_integrated_unit.empty() && - static_info.type != MechanicalUnitType::UNDEFINED && - !axes.fail() && !axes_total.fail()) - { - result = true; - } + // Basic verification. + if(!static_info.task_name.empty() && + !static_info.is_integrated_unit.empty() && + !static_info.has_integrated_unit.empty() && + static_info.type != MechanicalUnitType::UNDEFINED && + !axes.fail() && !axes_total.fail()) + { + ; + } + else + { + throw std::logic_error("RWSInterface::getMechanicalUnitStaticInfo(): inconsistent data"); } - - return result; } -bool RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, MechanicalUnitDynamicInfo& dynamic_info) +void RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, MechanicalUnitDynamicInfo& dynamic_info) { bool result = false; RWSResult rws_result = rws_client_.getMechanicalUnitDynamicInfo(mechunit); - if(rws_result.success) + dynamic_info.tool_name = xmlFindTextContent(rws_result, XMLAttribute("class", "tool-name")); + dynamic_info.wobj_name = xmlFindTextContent(rws_result, XMLAttribute("class", "wobj-name")); + dynamic_info.payload_name = xmlFindTextContent(rws_result, + XMLAttribute("class", "payload-name")); + dynamic_info.total_payload_name = xmlFindTextContent(rws_result, + XMLAttribute("class", "total-payload-name")); + dynamic_info.status = xmlFindTextContent(rws_result, XMLAttribute("class", "status")); + dynamic_info.jog_mode = xmlFindTextContent(rws_result, XMLAttribute("class", "jog-mode")); + std::string mode = xmlFindTextContent(rws_result, XMLAttribute("class", "mode")); + std::string coord_system = xmlFindTextContent(rws_result, XMLAttribute("class", "coord-system")); + + // Assume mechanical unit mode is unknown, update based on contents of 'mode'. + dynamic_info.mode = MechanicalUnitMode::UNKNOWN_MODE; + + if(mode == "Activated") { - dynamic_info.tool_name = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "tool-name")); - dynamic_info.wobj_name = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "wobj-name")); - dynamic_info.payload_name = xmlFindTextContent(rws_result.p_xml_document, - XMLAttribute("class", "payload-name")); - dynamic_info.total_payload_name = xmlFindTextContent(rws_result.p_xml_document, - XMLAttribute("class", "total-payload-name")); - dynamic_info.status = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "status")); - dynamic_info.jog_mode = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "jog-mode")); - std::string mode = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "mode")); - std::string coord_system = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "coord-system")); - - // Assume mechanical unit mode is unknown, update based on contents of 'mode'. - dynamic_info.mode = MechanicalUnitMode::UNKNOWN_MODE; - - if(mode == "Activated") - { - dynamic_info.mode = MechanicalUnitMode::ACTIVATED; - } - else if(mode == "Deactivated") - { - dynamic_info.mode = MechanicalUnitMode::DEACTIVATED; - } - - // Assume mechanical unit coordinate system is world, update based on contents of 'coord_system'. - dynamic_info.coord_system = Coordinate::WORLD; + dynamic_info.mode = MechanicalUnitMode::ACTIVATED; + } + else if(mode == "Deactivated") + { + dynamic_info.mode = MechanicalUnitMode::DEACTIVATED; + } - if(coord_system == "Base") - { - dynamic_info.coord_system = Coordinate::BASE; - } - else if(coord_system == "Tool") - { - dynamic_info.coord_system = Coordinate::TOOL; - } - else if(coord_system == "Wobj") - { - dynamic_info.coord_system = Coordinate::WOBJ; - } + // Assume mechanical unit coordinate system is world, update based on contents of 'coord_system'. + dynamic_info.coord_system = Coordinate::WORLD; - // Basic verification. - if(!dynamic_info.tool_name.empty() && - !dynamic_info.wobj_name.empty() && - !dynamic_info.payload_name.empty() && - !dynamic_info.total_payload_name.empty() && - !dynamic_info.status.empty() && - !dynamic_info.jog_mode.empty() && - dynamic_info.mode != MechanicalUnitMode::UNKNOWN_MODE) - { - result = true; - } + if(coord_system == "Base") + { + dynamic_info.coord_system = Coordinate::BASE; + } + else if(coord_system == "Tool") + { + dynamic_info.coord_system = Coordinate::TOOL; + } + else if(coord_system == "Wobj") + { + dynamic_info.coord_system = Coordinate::WOBJ; } - return result; + // Basic verification. + if(!dynamic_info.tool_name.empty() && + !dynamic_info.wobj_name.empty() && + !dynamic_info.payload_name.empty() && + !dynamic_info.total_payload_name.empty() && + !dynamic_info.status.empty() && + !dynamic_info.jog_mode.empty() && + dynamic_info.mode != MechanicalUnitMode::UNKNOWN_MODE) + { + ; + } + else + { + throw std::logic_error("RWSInterface::getMechanicalUnitDynamicInfo: inconsistent data"); + } } -bool RWSInterface::getMechanicalUnitJointTarget(const std::string& mechunit, JointTarget* p_jointtarget) +void RWSInterface::getMechanicalUnitJointTarget(const std::string& mechunit, JointTarget* p_jointtarget) { - bool result = false; - if (p_jointtarget) { RWSResult rws_result = rws_client_.getMechanicalUnitJointTarget(mechunit); - result = rws_result.success; - - if (result) - { - std::stringstream ss; - - ss << "[[" - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "rax_1")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "rax_2")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "rax_3")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "rax_4")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "rax_5")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "rax_6")) << "], [" - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_a")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_b")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_c")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_d")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_e")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_f")) << "]]"; - - p_jointtarget->parseString(ss.str()); - } + std::stringstream ss; + + ss << "[[" + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_1")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_2")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_3")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_4")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_5")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_6")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_a")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_b")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_c")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_d")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_e")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_f")) << "]]"; + + p_jointtarget->parseString(ss.str()); } - - return result; } -bool RWSInterface::getMechanicalUnitRobTarget(const std::string& mechunit, +void RWSInterface::getMechanicalUnitRobTarget(const std::string& mechunit, RobTarget* p_robtarget, Coordinate coordinate, const std::string& tool, const std::string& wobj) { - bool result = false; - if (p_robtarget) { RWSResult rws_result = rws_client_.getMechanicalUnitRobTarget(mechunit, coordinate, tool, wobj); - result = rws_result.success; - if (result) - { - std::stringstream ss; - - ss << "[[" - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "x")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "y")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "z")) << "], [" - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "q1")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "q2")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "q3")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "q4")) << "], [" - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "cf1")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "cf4")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "cf6")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "cfx")) << "], [" - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_a")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_b")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_c")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_d")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_e")) << "," - << xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "eax_f")) << "]]"; - - p_robtarget->parseString(ss.str()); - } + std::stringstream ss; + + ss << "[[" + << xmlFindTextContent(rws_result, XMLAttribute("class", "x")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "y")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "z")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "q1")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "q2")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "q3")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "q4")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "cf1")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "cf4")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "cf6")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "cfx")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_a")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_b")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_c")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_d")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_e")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_f")) << "]]"; + + p_robtarget->parseString(ss.str()); } - - return result; } -bool RWSInterface::setRAPIDSymbolData(const std::string& task, +void RWSInterface::setRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name, const std::string& data) { - return rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data).success; + rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data); } -bool RWSInterface::setRAPIDSymbolData(const std::string& task, +void RWSInterface::setRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name, const RAPIDSymbolDataAbstract& data) { - return rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data).success; + rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data); } -bool RWSInterface::setRAPIDSymbolData(const std::string& task, +void RWSInterface::setRAPIDSymbolData(const std::string& task, const RAPIDSymbolResource& symbol, const RAPIDSymbolDataAbstract& data) { - return rws_client_.setRAPIDSymbolData(RAPIDResource(task, symbol), data).success; + rws_client_.setRAPIDSymbolData(RAPIDResource(task, symbol), data); } -bool RWSInterface::startRAPIDExecution() +void RWSInterface::startRAPIDExecution() { - return rws_client_.startRAPIDExecution().success; + rws_client_.startRAPIDExecution(); } -bool RWSInterface::stopRAPIDExecution() +void RWSInterface::stopRAPIDExecution() { - return rws_client_.stopRAPIDExecution().success; + rws_client_.stopRAPIDExecution(); } -bool RWSInterface::resetRAPIDProgramPointer() +void RWSInterface::resetRAPIDProgramPointer() { - return rws_client_.resetRAPIDProgramPointer().success; + rws_client_.resetRAPIDProgramPointer(); } -bool RWSInterface::setMotorsOn() +void RWSInterface::setMotorsOn() { - return rws_client_.setMotorsOn().success; + rws_client_.setMotorsOn(); } -bool RWSInterface::setMotorsOff() +void RWSInterface::setMotorsOff() { - return rws_client_.setMotorsOff().success; + rws_client_.setMotorsOff(); } -bool RWSInterface::setSpeedRatio(unsigned int ratio) +void RWSInterface::setSpeedRatio(unsigned int ratio) { - return rws_client_.setSpeedRatio(ratio).success; + rws_client_.setSpeedRatio(ratio); } std::vector RWSInterface::getRAPIDModulesInfo(const std::string& task) @@ -836,7 +798,7 @@ std::vector RWSInterface::getRAPIDModulesInfo(const std::string std::vector result; RWSResult rws_result = rws_client_.getRAPIDModulesInfo(task); - std::vector node_list = xmlFindNodes(rws_result.p_xml_document, + std::vector node_list = xmlFindNodes(rws_result, XMLAttributes::CLASS_RAP_MODULE_INFO_LI); for (size_t i = 0; i < node_list.size(); ++i) @@ -855,7 +817,7 @@ std::vector RWSInterface::getRAPIDTasks() std::vector result; RWSResult rws_result = rws_client_.getRAPIDTasks(); - std::vector node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_RAP_TASK_LI); + std::vector node_list = xmlFindNodes(rws_result, XMLAttributes::CLASS_RAP_TASK_LI); for (size_t i = 0; i < node_list.size(); ++i) { @@ -895,9 +857,8 @@ unsigned int RWSInterface::getSpeedRatio() unsigned int speed_ratio = 0; RWSResult rws_result = rws_client_.getSpeedRatio(); - if(!rws_result.success) throw std::runtime_error("Failed to get the speed ratio"); - - std::stringstream ss(xmlFindTextContent(rws_result.p_xml_document, XMLAttribute(Identifiers::CLASS, "speedratio"))); + + std::stringstream ss(xmlFindTextContent(rws_result, XMLAttribute(Identifiers::CLASS, "speedratio"))); ss >> speed_ratio; if(ss.fail()) throw std::runtime_error("Failed to parse the speed ratio"); @@ -910,87 +871,87 @@ SystemInfo RWSInterface::getSystemInfo() RWSResult rws_result = rws_client_.getRobotWareSystem(); - std::vector node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_SYS_SYSTEM_LI); + std::vector node_list = xmlFindNodes(rws_result, XMLAttributes::CLASS_SYS_SYSTEM_LI); for (size_t i = 0; i < node_list.size(); ++i) { result.system_name = xmlFindTextContent(node_list.at(i), XMLAttributes::CLASS_NAME); result.robot_ware_version = xmlFindTextContent(node_list.at(i), XMLAttributes::CLASS_RW_VERSION_NAME); } - node_list = xmlFindNodes(rws_result.p_xml_document, XMLAttributes::CLASS_SYS_OPTION_LI); + node_list = xmlFindNodes(rws_result, XMLAttributes::CLASS_SYS_OPTION_LI); for (size_t i = 0; i < node_list.size(); ++i) { result.system_options.push_back(xmlFindTextContent(node_list.at(i), XMLAttributes::CLASS_OPTION)); } - result.system_type = xmlFindTextContent(rws_client_.getContollerService().p_xml_document, + result.system_type = xmlFindTextContent(rws_client_.getContollerService(), XMLAttributes::CLASS_CTRL_TYPE); return result; } -TriBool RWSInterface::isAutoMode() +bool RWSInterface::isAutoMode() { return compareSingleContent(rws_client_.getPanelOperationMode(), XMLAttributes::CLASS_OPMODE, ContollerStates::PANEL_OPERATION_MODE_AUTO); } -TriBool RWSInterface::isMotorsOn() +bool RWSInterface::isMotorsOn() { return compareSingleContent(rws_client_.getPanelControllerState(), XMLAttributes::CLASS_CTRLSTATE, ContollerStates::CONTROLLER_MOTOR_ON); } -TriBool RWSInterface::isRAPIDRunning() +bool RWSInterface::isRAPIDRunning() { return compareSingleContent(rws_client_.getRAPIDExecution(), XMLAttributes::CLASS_CTRLEXECSTATE, ContollerStates::RAPID_EXECUTION_RUNNING); } -bool RWSInterface::setIOSignal(const std::string& iosignal, const std::string& value) +void RWSInterface::setIOSignal(const std::string& iosignal, const std::string& value) { - return rws_client_.setIOSignal(iosignal, value).success; + rws_client_.setIOSignal(iosignal, value); } std::string RWSInterface::getRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name) { - return xmlFindTextContent(rws_client_.getRAPIDSymbolData(RAPIDResource(task, module, name)).p_xml_document, + return xmlFindTextContent(rws_client_.getRAPIDSymbolData(RAPIDResource(task, module, name)), XMLAttributes::CLASS_VALUE); } -bool RWSInterface::getRAPIDSymbolData(const std::string& task, +void RWSInterface::getRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name, - RAPIDSymbolDataAbstract* p_data) + RAPIDSymbolDataAbstract& data) { - return rws_client_.getRAPIDSymbolData(RAPIDResource(task, module, name), p_data).success; + rws_client_.getRAPIDSymbolData(RAPIDResource(task, module, name), data); } -bool RWSInterface::getRAPIDSymbolData(const std::string& task, +void RWSInterface::getRAPIDSymbolData(const std::string& task, const RAPIDSymbolResource& symbol, - RAPIDSymbolDataAbstract* p_data) + RAPIDSymbolDataAbstract& data) { - return rws_client_.getRAPIDSymbolData(RAPIDResource(task, symbol), p_data).success; + rws_client_.getRAPIDSymbolData(RAPIDResource(task, symbol), data); } -bool RWSInterface::getFile(const FileResource& resource, std::string* p_file_content) +void RWSInterface::getFile(const FileResource& resource, std::string* p_file_content) { - return rws_client_.getFile(resource, p_file_content).success; + rws_client_.getFile(resource, p_file_content); } -bool RWSInterface::uploadFile(const FileResource& resource, const std::string& file_content) +void RWSInterface::uploadFile(const FileResource& resource, const std::string& file_content) { - return rws_client_.uploadFile(resource, file_content).success; + rws_client_.uploadFile(resource, file_content); } -bool RWSInterface::deleteFile(const FileResource& resource) +void RWSInterface::deleteFile(const FileResource& resource) { - return rws_client_.deleteFile(resource).success; + rws_client_.deleteFile(resource); } SubscriptionGroup RWSInterface::openSubscription (const SubscriptionResources& resources) @@ -998,18 +959,18 @@ SubscriptionGroup RWSInterface::openSubscription (const SubscriptionResources& r return {rws_client_, resources}; } -bool RWSInterface::registerLocalUser(const std::string& username, +void RWSInterface::registerLocalUser(const std::string& username, const std::string& application, const std::string& location) { - return rws_client_.registerLocalUser(username, application, location).success; + rws_client_.registerLocalUser(username, application, location); } -bool RWSInterface::registerRemoteUser(const std::string& username, +void RWSInterface::registerRemoteUser(const std::string& username, const std::string& application, const std::string& location) { - return rws_client_.registerRemoteUser(username, application, location).success; + rws_client_.registerRemoteUser(username, application, location); } std::string RWSInterface::getLogText(const bool verbose) @@ -1026,19 +987,11 @@ std::string RWSInterface::getLogTextLatestEvent(const bool verbose) * Auxiliary methods */ -TriBool RWSInterface::compareSingleContent(const RWSResult& rws_result, +bool RWSInterface::compareSingleContent(const RWSResult& rws_result, const XMLAttribute& attribute, const std::string& compare_string) { - TriBool result; - - if (rws_result.success) - { - std::string temp = xmlFindTextContent(rws_result.p_xml_document, attribute); - result = (temp == compare_string); - } - - return result; + return xmlFindTextContent(rws_result, attribute) == compare_string; } } // end namespace rws diff --git a/src/rws_poco_client.cpp b/src/rws_poco_client.cpp index 1f47c12e..b9f08682 100644 --- a/src/rws_poco_client.cpp +++ b/src/rws_poco_client.cpp @@ -84,14 +84,14 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, // Lock the object's mutex. It is released when the method goes out of scope. ScopedLock lock(http_mutex_); - // Result of the communication. - POCOResult result; - // The response and the request. HTTPResponse response; + std::string response_content; + HTTPRequest request(method, uri, HTTPRequest::HTTP_1_1); request.setCookies(cookies_); request.setContentLength(content.length()); + if (method == HTTPRequest::HTTP_POST || !content.empty()) { request.setContentType("application/x-www-form-urlencoded"); @@ -100,7 +100,7 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, // Attempt the communication. try { - sendAndReceive(result, request, response, content); + sendAndReceive(request, response, content, response_content); // Check if the server has sent an update for the cookies. std::vector temp_cookies; @@ -122,16 +122,17 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, { http_client_session_.reset(); request.erase(HTTPRequest::COOKIE); - sendAndReceive(result, request, response, content); + sendAndReceive(request, response, content, response_content); } // Check if the request was unauthorized, if so add credentials. if (response.getStatus() == HTTPResponse::HTTP_UNAUTHORIZED) { - authenticate(result, request, response, content); + authenticate(request, response, content, response_content); } - result.status = POCOResult::OK; + + return POCOResult {response.getStatus(), response, response_content}; } catch (Poco::Exception const&) { @@ -140,13 +141,10 @@ POCOResult POCOClient::makeHTTPRequest(const std::string& method, throw; } - - return result; } -Poco::Net::WebSocket POCOClient::webSocketConnect(const std::string& uri, - const std::string& protocol) +Poco::Net::WebSocket POCOClient::webSocketConnect(const std::string& uri, const std::string& protocol) { // Lock the object's mutex. It is released when the method goes out of scope. ScopedLock lock(http_mutex_); @@ -179,27 +177,39 @@ Poco::Net::WebSocket POCOClient::webSocketConnect(const std::string& uri, * Auxiliary methods */ -void POCOClient::sendAndReceive(POCOResult& result, - HTTPRequest& request, +void POCOClient::sendAndReceive(HTTPRequest& request, HTTPResponse& response, - const std::string& request_content) + const std::string& request_content, + std::string& response_content) { - // Add request info to the result. - result.addHTTPRequestInfo(request, request_content); + HTTPInfo log_entry; + + // Add request info to the log entry. + log_entry.addHTTPRequestInfo(request, request_content); // Contact the server. - std::string response_content; http_client_session_.sendRequest(request) << request_content; + + response_content.clear(); StreamCopier::copyToString(http_client_session_.receiveResponse(response), response_content); - // Add response info to the result. - result.addHTTPResponseInfo(response, response_content); + // Add response info to the log entry. + log_entry.addHTTPResponseInfo(response, response_content); + + // Add entry to the log + if (log_.size() >= LOG_SIZE) + { + log_.pop_back(); + } + + log_.push_front(log_entry); } -void POCOClient::authenticate(POCOResult& result, - HTTPRequest& request, + +void POCOClient::authenticate(HTTPRequest& request, HTTPResponse& response, - const std::string& request_content) + const std::string& request_content, + std::string& response_content) { // Remove any old cookies. cookies_.clear(); @@ -208,7 +218,7 @@ void POCOClient::authenticate(POCOResult& result, http_credentials_.authenticate(request, response); // Contact the server, and extract and store the received cookies. - sendAndReceive(result, request, response, request_content); + sendAndReceive(request, response, request_content, response_content); std::vector temp_cookies; response.getCookies(temp_cookies); @@ -234,5 +244,79 @@ void POCOClient::extractAndStoreCookie(const std::string& cookie_string) } } + +std::string POCOClient::getLogText(bool verbose) const +{ + if (log_.size() == 0) + { + return ""; + } + + std::stringstream ss; + + for (size_t i = 0; i < log_.size(); ++i) + { + std::stringstream temp; + temp << i + 1 << ". "; + ss << temp.str() << log_[i].toString(verbose, temp.str().size()) << std::endl; + } + + return ss.str(); +} + + +std::string POCOClient::getLogTextLatestEvent(bool verbose) const +{ + return (log_.size() == 0 ? "" : log_[0].toString(verbose, 0)); +} + + +void POCOClient::HTTPInfo::addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, + const std::string& request_content) +{ + this->request = {request.getMethod(), request.getURI(), request_content}; +} + + +void POCOClient::HTTPInfo::addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, + const std::string& response_content) +{ + std::string header_info; + + for (HTTPResponse::ConstIterator i = response.begin(); i != response.end(); ++i) + { + header_info += i->first + "=" + i->second + "\n"; + } + + this->response = HTTPInfo::ResponseInfo {response.getStatus(), header_info, response_content}; +} + + +std::string POCOClient::HTTPInfo::toString(bool verbose, size_t indent) const +{ + std::stringstream ss; + + std::string seperator = (indent == 0 ? " | " : "\n" + std::string(indent, ' ')); + + if (request) + { + ss << seperator << "HTTP Request: " << request->method << " " << request->uri; + } + + if (response) + { + ss << seperator << "HTTP Response: " << response->status << " - " + << HTTPResponse::getReasonForStatus(response->status); + + if (verbose) + { + ss << seperator << "HTTP Response Content: " << response->content; + } + } + + return ss.str(); +} + + } // end namespace rws } // end namespace abb diff --git a/src/rws_poco_result.cpp b/src/rws_poco_result.cpp index de051600..ed689e73 100644 --- a/src/rws_poco_result.cpp +++ b/src/rws_poco_result.cpp @@ -14,104 +14,11 @@ namespace abb :: rws /*********************************************************************************************************************** * Struct definitions: POCOResult */ - - /************************************************************ - * Primary methods - */ - - void POCOResult::addHTTPRequestInfo(const Poco::Net::HTTPRequest& request, - const std::string& request_content) - { - poco_info.http.request.method = request.getMethod(); - poco_info.http.request.uri = request.getURI(); - poco_info.http.request.content = request_content; - } - - void POCOResult::addHTTPResponseInfo(const Poco::Net::HTTPResponse& response, - const std::string& response_content) - { - std::string header_info; - - for (HTTPResponse::ConstIterator i = response.begin(); i != response.end(); ++i) - { - header_info += i->first + "=" + i->second + "\n"; - } - - poco_info.http.response.status = response.getStatus(); - poco_info.http.response.header_info = header_info; - poco_info.http.response.content = response_content; - } - - /************************************************************ - * Auxiliary methods - */ - - std::string POCOResult::mapGeneralStatus() const - { - std::string result; - - switch (status) - { - case POCOResult::UNKNOWN: - result = "UNKNOWN"; - break; - - case POCOResult::OK: - result = "OK"; - break; - - case POCOResult::WEBSOCKET_NOT_ALLOCATED: - result = "WEBSOCKET_NOT_ALLOCATED"; - break; - - case POCOResult::EXCEPTION_POCO_INVALID_ARGUMENT: - result = "EXCEPTION_POCO_INVALID_ARGUMENT"; - break; - - case POCOResult::EXCEPTION_POCO_TIMEOUT: - result = "EXCEPTION_POCO_TIMEOUT"; - break; - - case POCOResult::EXCEPTION_POCO_NET: - result = "EXCEPTION_POCO_NET"; - break; - - case POCOResult::EXCEPTION_POCO_WEBSOCKET: - result = "EXCEPTION_POCO_WEBSOCKET"; - break; - - default: - result = "UNDEFINED"; - break; - } - - return result; - } - - std::string POCOResult::toString(const bool verbose, const size_t indent) const + POCOResult::POCOResult(Poco::Net::HTTPResponse::HTTPStatus http_status, + Poco::Net::NameValueCollection const& header_info, std::string const& content) + : httpStatus_ {http_status} + , headerInfo_(header_info.begin(), header_info.end()) + , content_ {content} { - std::stringstream ss; - - std::string seperator = (indent == 0 ? " | " : "\n" + std::string(indent, ' ')); - - ss << "General status: " << mapGeneralStatus(); - - if (!poco_info.http.request.method.empty()) - { - ss << seperator << "HTTP Request: " << poco_info.http.request.method << " " << poco_info.http.request.uri; - - if (status == OK) - { - ss << seperator << "HTTP Response: " << poco_info.http.response.status << " - " - << HTTPResponse::getReasonForStatus(poco_info.http.response.status); - - if (verbose) - { - ss << seperator << "HTTP Response Content: " << poco_info.http.response.content; - } - } - } - - return ss.str(); - } + }; } \ No newline at end of file diff --git a/src/rws_state_machine_interface.cpp b/src/rws_state_machine_interface.cpp index 96e6996d..ffbbbbf1 100644 --- a/src/rws_state_machine_interface.cpp +++ b/src/rws_state_machine_interface.cpp @@ -111,68 +111,63 @@ EGMActions RWSStateMachineInterface::Services::EGM::getCurrentAction(const std:: EGMActions result; RAPIDNum temp_current_action; - if (p_rws_interface_->getRAPIDSymbolData(task, Symbols::EGM_CURRENT_ACTION, &temp_current_action)) + p_rws_interface_->getRAPIDSymbolData(task, Symbols::EGM_CURRENT_ACTION, temp_current_action); + + switch ((int) temp_current_action.value) { - switch ((int) temp_current_action.value) - { - case EGM_ACTION_STOP: - result = EGM_ACTION_STOP; - break; + case EGM_ACTION_STOP: + result = EGM_ACTION_STOP; + break; - case EGM_ACTION_RUN_JOINT: - result = EGM_ACTION_RUN_JOINT; - break; + case EGM_ACTION_RUN_JOINT: + result = EGM_ACTION_RUN_JOINT; + break; - case EGM_ACTION_RUN_POSE: - result = EGM_ACTION_RUN_POSE; - break; + case EGM_ACTION_RUN_POSE: + result = EGM_ACTION_RUN_POSE; + break; - default: - result = EGM_ACTION_UNKNOWN; - break; - } - } - else - { - result = EGM_ACTION_UNKNOWN; + default: + result = EGM_ACTION_UNKNOWN; + break; } return result; } -bool RWSStateMachineInterface::Services::EGM::getSettings(const std::string& task, EGMSettings* p_settings) const +void RWSStateMachineInterface::Services::EGM::getSettings(const std::string& task, EGMSettings* p_settings) const { - return p_rws_interface_->getRAPIDSymbolData(task, Symbols::EGM_SETTINGS, p_settings); + p_rws_interface_->getRAPIDSymbolData(task, Symbols::EGM_SETTINGS, *p_settings); } -bool RWSStateMachineInterface::Services::EGM::setSettings(const std::string& task, const EGMSettings& settings) const +void RWSStateMachineInterface::Services::EGM::setSettings(const std::string& task, const EGMSettings& settings) const { - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::EGM_SETTINGS, settings); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::EGM_SETTINGS, settings); } -bool RWSStateMachineInterface::Services::EGM::signalEGMStartJoint() const +void RWSStateMachineInterface::Services::EGM::signalEGMStartJoint() const { - return p_rws_interface_->toggleIOSignal(IOSignals::EGM_START_JOINT); + p_rws_interface_->toggleIOSignal(IOSignals::EGM_START_JOINT); } -bool RWSStateMachineInterface::Services::EGM::signalEGMStartPose() const +void RWSStateMachineInterface::Services::EGM::signalEGMStartPose() const { - return p_rws_interface_->toggleIOSignal(IOSignals::EGM_START_POSE); + p_rws_interface_->toggleIOSignal(IOSignals::EGM_START_POSE); } -bool RWSStateMachineInterface::Services::EGM::signalEGMStartStream() const +void RWSStateMachineInterface::Services::EGM::signalEGMStartStream() const { - return p_rws_interface_->toggleIOSignal(IOSignals::EGM_START_STREAM); + p_rws_interface_->toggleIOSignal(IOSignals::EGM_START_STREAM); } -bool RWSStateMachineInterface::Services::EGM::signalEGMStop() const +void RWSStateMachineInterface::Services::EGM::signalEGMStop() const { - return p_rws_interface_->toggleIOSignal(IOSignals::EGM_STOP); + p_rws_interface_->toggleIOSignal(IOSignals::EGM_STOP); } -bool RWSStateMachineInterface::Services::EGM::signalEGMStopStream() const +void RWSStateMachineInterface::Services::EGM::signalEGMStopStream() const { - return p_rws_interface_->toggleIOSignal(IOSignals::EGM_STOP_STREAM); + p_rws_interface_->toggleIOSignal(IOSignals::EGM_STOP_STREAM); } @@ -188,69 +183,42 @@ bool RWSStateMachineInterface::Services::EGM::signalEGMStopStream() const States RWSStateMachineInterface::Services::Main::getCurrentState(const std::string& task) const { - States result; + States result = STATE_UNKNOWN; RAPIDNum temp_current_state; + p_rws_interface_->getRAPIDSymbolData(task, Symbols::MAIN_CURRENT_STATE, temp_current_state); - if (p_rws_interface_->getRAPIDSymbolData(task, Symbols::MAIN_CURRENT_STATE, &temp_current_state)) + switch (static_cast(temp_current_state.value)) { - switch ((int) temp_current_state.value) - { - case STATE_IDLE: - result = STATE_IDLE; - break; + case STATE_IDLE: + result = STATE_IDLE; + break; - case STATE_INITIALIZE: - result = STATE_INITIALIZE; - break; + case STATE_INITIALIZE: + result = STATE_INITIALIZE; + break; - case STATE_RUN_RAPID_ROUTINE: - result = STATE_RUN_RAPID_ROUTINE; - break; + case STATE_RUN_RAPID_ROUTINE: + result = STATE_RUN_RAPID_ROUTINE; + break; - case STATE_RUN_EGM_ROUTINE: - result = STATE_RUN_EGM_ROUTINE; - break; - - default: - result = STATE_UNKNOWN; - break; - } - } - else - { - result = STATE_UNKNOWN; + case STATE_RUN_EGM_ROUTINE: + result = STATE_RUN_EGM_ROUTINE; + break; } return result; } -TriBool RWSStateMachineInterface::Services::Main::isStateIdle(const std::string& task) const - +bool RWSStateMachineInterface::Services::Main::isStateIdle(const std::string& task) const { - TriBool result; - States temp_current_state = getCurrentState(task); - - if (temp_current_state != STATE_UNKNOWN) - { - result = (temp_current_state == STATE_IDLE); - } - - return result; + return getCurrentState(task) == STATE_IDLE; } -TriBool RWSStateMachineInterface::Services::Main::isStationary(const std::string& mechanical_unit) const -{ - TriBool result; - - std::string temp_stationary = p_rws_interface_->getIOSignal(IOSignals::OUTPUT_STATIONARY + "_" + mechanical_unit); - if (!temp_stationary.empty()) - { - result = (temp_stationary == SystemConstants::IOSignals::HIGH); - } - - return result; +bool RWSStateMachineInterface::Services::Main::isStationary(const std::string& mechanical_unit) const +{ + return p_rws_interface_->getIOSignal(IOSignals::OUTPUT_STATIONARY + "_" + mechanical_unit) == SystemConstants::IOSignals::HIGH; } @@ -264,66 +232,72 @@ TriBool RWSStateMachineInterface::Services::Main::isStationary(const std::string * Primary methods */ -bool RWSStateMachineInterface::Services::RAPID::runCallByVar(const std::string& task, +void RWSStateMachineInterface::Services::RAPID::runCallByVar(const std::string& task, const std::string& routine_name, const unsigned int routine_number) const { RAPIDString temp_routine_name(routine_name); RAPIDNum temp_routine_number(routine_number); - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_CALL_BY_VAR_NAME_INPUT, temp_routine_name) && - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_CALL_BY_VAR_NUM_INPUT, temp_routine_number) && - setRoutineName(task, Procedures::RUN_CALL_BY_VAR) && signalRunRAPIDRoutine(); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_CALL_BY_VAR_NAME_INPUT, temp_routine_name); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_CALL_BY_VAR_NUM_INPUT, temp_routine_number); + setRoutineName(task, Procedures::RUN_CALL_BY_VAR); + signalRunRAPIDRoutine(); } -bool RWSStateMachineInterface::Services::RAPID::runModuleLoad(const std::string& task, +void RWSStateMachineInterface::Services::RAPID::runModuleLoad(const std::string& task, const std::string& file_path) const { RAPIDString temp_file_path(file_path); - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MODULE_FILE_PATH_INPUT, temp_file_path) && - setRoutineName(task, Procedures::RUN_MODULE_LOAD) && signalRunRAPIDRoutine(); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MODULE_FILE_PATH_INPUT, temp_file_path); + setRoutineName(task, Procedures::RUN_MODULE_LOAD); + signalRunRAPIDRoutine(); } -bool RWSStateMachineInterface::Services::RAPID::runModuleUnload(const std::string& task, +void RWSStateMachineInterface::Services::RAPID::runModuleUnload(const std::string& task, const std::string& file_path) const { RAPIDString temp_file_path(file_path); - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MODULE_FILE_PATH_INPUT, temp_file_path) && - setRoutineName(task, Procedures::RUN_MODULE_UNLOAD) && signalRunRAPIDRoutine(); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MODULE_FILE_PATH_INPUT, temp_file_path); + setRoutineName(task, Procedures::RUN_MODULE_UNLOAD); + signalRunRAPIDRoutine(); } -bool RWSStateMachineInterface::Services::RAPID::runMoveAbsJ(const std::string& task, +void RWSStateMachineInterface::Services::RAPID::runMoveAbsJ(const std::string& task, const JointTarget& joint_target) const { - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_JOINT_TARGET_INPUT, joint_target) && - setRoutineName(task, Procedures::RUN_MOVE_ABS_J) && signalRunRAPIDRoutine(); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_JOINT_TARGET_INPUT, joint_target); + setRoutineName(task, Procedures::RUN_MOVE_ABS_J); + signalRunRAPIDRoutine(); } -bool RWSStateMachineInterface::Services::RAPID::runMoveJ(const std::string& task, const RobTarget& rob_target) const +void RWSStateMachineInterface::Services::RAPID::runMoveJ(const std::string& task, const RobTarget& rob_target) const { - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_ROB_TARGET_INPUT, rob_target) && - setRoutineName(task, Procedures::RUN_MOVE_J) && signalRunRAPIDRoutine(); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_ROB_TARGET_INPUT, rob_target); + setRoutineName(task, Procedures::RUN_MOVE_J); + signalRunRAPIDRoutine(); } -bool RWSStateMachineInterface::Services::RAPID::runMoveToCalibrationPosition(const std::string& task) const +void RWSStateMachineInterface::Services::RAPID::runMoveToCalibrationPosition(const std::string& task) const { - return setRoutineName(task, Procedures::RUN_MOVE_TO_CALIBRATION_POSITION) && signalRunRAPIDRoutine(); + setRoutineName(task, Procedures::RUN_MOVE_TO_CALIBRATION_POSITION); + signalRunRAPIDRoutine(); } -bool RWSStateMachineInterface::Services::RAPID::setMoveSpeed(const std::string& task, const SpeedData& speed_data) const +void RWSStateMachineInterface::Services::RAPID::setMoveSpeed(const std::string& task, const SpeedData& speed_data) const { - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_SPEED_INPUT, speed_data); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_SPEED_INPUT, speed_data); } -bool RWSStateMachineInterface::Services::RAPID::setRoutineName(const std::string& task, +void RWSStateMachineInterface::Services::RAPID::setRoutineName(const std::string& task, const std::string& routine_name) const { RAPIDString temp_routine_name(routine_name); - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_ROUTINE_NAME_INPUT, temp_routine_name); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_ROUTINE_NAME_INPUT, temp_routine_name); } -bool RWSStateMachineInterface::Services::RAPID::signalRunRAPIDRoutine() const +void RWSStateMachineInterface::Services::RAPID::signalRunRAPIDRoutine() const { - return p_rws_interface_->toggleIOSignal(IOSignals::RUN_RAPID_ROUTINE); + p_rws_interface_->toggleIOSignal(IOSignals::RUN_RAPID_ROUTINE); } @@ -337,346 +311,346 @@ bool RWSStateMachineInterface::Services::RAPID::signalRunRAPIDRoutine() const * Primary methods */ -bool RWSStateMachineInterface::Services::SG::dualBlow1Off() const +void RWSStateMachineInterface::Services::SG::dualBlow1Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualBlow1On() const +void RWSStateMachineInterface::Services::SG::dualBlow1On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualBlow2Off() const +void RWSStateMachineInterface::Services::SG::dualBlow2Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualBlow2On() const +void RWSStateMachineInterface::Services::SG::dualBlow2On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualCalibrate() const +void RWSStateMachineInterface::Services::SG::dualCalibrate() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_CALIBRATE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_CALIBRATE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_CALIBRATE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_CALIBRATE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualGetSettings(SGSettings* p_left_settings, +void RWSStateMachineInterface::Services::SG::dualGetSettings(SGSettings* p_left_settings, SGSettings* p_right_settings) const { - return getSettings(SystemConstants::RAPID::TASK_ROB_L, p_left_settings) && - getSettings(SystemConstants::RAPID::TASK_ROB_R, p_right_settings); + getSettings(SystemConstants::RAPID::TASK_ROB_L, p_left_settings); + getSettings(SystemConstants::RAPID::TASK_ROB_R, p_right_settings); } -bool RWSStateMachineInterface::Services::SG::dualGripIn() const +void RWSStateMachineInterface::Services::SG::dualGripIn() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_IN) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_IN) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_IN); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_IN); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualGripOut() const +void RWSStateMachineInterface::Services::SG::dualGripOut() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_OUT) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_OUT) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_OUT); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_OUT); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualInitialize() const +void RWSStateMachineInterface::Services::SG::dualInitialize() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_INITIALIZE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_INITIALIZE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_INITIALIZE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_INITIALIZE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualMoveTo(const float left_position, const float right_position) const +void RWSStateMachineInterface::Services::SG::dualMoveTo(const float left_position, const float right_position) const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_MOVE_TO) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_MOVE_TO) && - setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_L, left_position) && - setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_R, right_position) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_MOVE_TO); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_MOVE_TO); + setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_L, left_position); + setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_R, right_position); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualSetSettings(const SGSettings& left_settings, +void RWSStateMachineInterface::Services::SG::dualSetSettings(const SGSettings& left_settings, const SGSettings& right_settings) const { - return setSettings(SystemConstants::RAPID::TASK_ROB_L, left_settings) && - setSettings(SystemConstants::RAPID::TASK_ROB_R, right_settings); + setSettings(SystemConstants::RAPID::TASK_ROB_L, left_settings); + setSettings(SystemConstants::RAPID::TASK_ROB_R, right_settings); } -bool RWSStateMachineInterface::Services::SG::dualVacuum1Off() const +void RWSStateMachineInterface::Services::SG::dualVacuum1Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualVacuum1On() const +void RWSStateMachineInterface::Services::SG::dualVacuum1On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualVacuum2Off() const +void RWSStateMachineInterface::Services::SG::dualVacuum2Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::dualVacuum2On() const +void RWSStateMachineInterface::Services::SG::dualVacuum2On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftBlow1Off() const +void RWSStateMachineInterface::Services::SG::leftBlow1Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftBlow1On() const +void RWSStateMachineInterface::Services::SG::leftBlow1On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftBlow2Off() const +void RWSStateMachineInterface::Services::SG::leftBlow2Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_OFF_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftBlow2On() const +void RWSStateMachineInterface::Services::SG::leftBlow2On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_BLOW_ON_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftCalibrate() const +void RWSStateMachineInterface::Services::SG::leftCalibrate() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_CALIBRATE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_CALIBRATE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftGetSettings(SGSettings* p_settings) const +void RWSStateMachineInterface::Services::SG::leftGetSettings(SGSettings* p_settings) const { - return getSettings(SystemConstants::RAPID::TASK_ROB_L, p_settings); + getSettings(SystemConstants::RAPID::TASK_ROB_L, p_settings); } -bool RWSStateMachineInterface::Services::SG::leftGripIn() const +void RWSStateMachineInterface::Services::SG::leftGripIn() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_IN) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_IN); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftGripOut() const +void RWSStateMachineInterface::Services::SG::leftGripOut() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_OUT) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_GRIP_OUT); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftInitialize() const +void RWSStateMachineInterface::Services::SG::leftInitialize() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_INITIALIZE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_INITIALIZE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftMoveTo(const float position) const +void RWSStateMachineInterface::Services::SG::leftMoveTo(const float position) const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_MOVE_TO) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_L, position) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_MOVE_TO); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_L, position); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftSetSettings(const SGSettings& settings) const +void RWSStateMachineInterface::Services::SG::leftSetSettings(const SGSettings& settings) const { - return setSettings(SystemConstants::RAPID::TASK_ROB_L, settings); + setSettings(SystemConstants::RAPID::TASK_ROB_L, settings); } -bool RWSStateMachineInterface::Services::SG::leftVacuum1Off() const +void RWSStateMachineInterface::Services::SG::leftVacuum1Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftVacuum1On() const +void RWSStateMachineInterface::Services::SG::leftVacuum1On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_1) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_1); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftVacuum2Off() const +void RWSStateMachineInterface::Services::SG::leftVacuum2Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_OFF_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::leftVacuum2On() const +void RWSStateMachineInterface::Services::SG::leftVacuum2On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_2) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_VACUUM_ON_2); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_NONE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightBlow1Off() const +void RWSStateMachineInterface::Services::SG::rightBlow1Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightBlow1On() const +void RWSStateMachineInterface::Services::SG::rightBlow1On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightBlow2Off() const +void RWSStateMachineInterface::Services::SG::rightBlow2Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_OFF_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightBlow2On() const +void RWSStateMachineInterface::Services::SG::rightBlow2On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_BLOW_ON_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightCalibrate() const +void RWSStateMachineInterface::Services::SG::rightCalibrate() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_CALIBRATE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_CALIBRATE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightGetSettings(SGSettings* p_settings) const +void RWSStateMachineInterface::Services::SG::rightGetSettings(SGSettings* p_settings) const { - return getSettings(SystemConstants::RAPID::TASK_ROB_R, p_settings); + getSettings(SystemConstants::RAPID::TASK_ROB_R, p_settings); } -bool RWSStateMachineInterface::Services::SG::rightGripIn() const +void RWSStateMachineInterface::Services::SG::rightGripIn() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_IN) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_IN); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightGripOut() const +void RWSStateMachineInterface::Services::SG::rightGripOut() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_OUT) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_GRIP_OUT); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightInitialize() const +void RWSStateMachineInterface::Services::SG::rightInitialize() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_INITIALIZE) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_INITIALIZE); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightMoveTo(const float position) const +void RWSStateMachineInterface::Services::SG::rightMoveTo(const float position) const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_MOVE_TO) && - setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_R, position) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_MOVE_TO); + setTargetPositionInput(SystemConstants::RAPID::TASK_ROB_R, position); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightSetSettings(const SGSettings& settings) const +void RWSStateMachineInterface::Services::SG::rightSetSettings(const SGSettings& settings) const { - return setSettings(SystemConstants::RAPID::TASK_ROB_R, settings); + setSettings(SystemConstants::RAPID::TASK_ROB_R, settings); } -bool RWSStateMachineInterface::Services::SG::rightVacuum1Off() const +void RWSStateMachineInterface::Services::SG::rightVacuum1Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightVacuum1On() const +void RWSStateMachineInterface::Services::SG::rightVacuum1On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_1) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_1); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightVacuum2Off() const +void RWSStateMachineInterface::Services::SG::rightVacuum2Off() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_OFF_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::rightVacuum2On() const +void RWSStateMachineInterface::Services::SG::rightVacuum2On() const { - return setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE) && - setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_2) && - signalRunSGRoutine(); + setCommandInput(SystemConstants::RAPID::TASK_ROB_L, SG_COMMAND_NONE); + setCommandInput(SystemConstants::RAPID::TASK_ROB_R, SG_COMMAND_VACUUM_ON_2); + signalRunSGRoutine(); } -bool RWSStateMachineInterface::Services::SG::signalRunSGRoutine() const +void RWSStateMachineInterface::Services::SG::signalRunSGRoutine() const { - return p_rws_interface_->toggleIOSignal(IOSignals::RUN_SG_ROUTINE); + p_rws_interface_->toggleIOSignal(IOSignals::RUN_SG_ROUTINE); } /************************************************************ * Auxiliary methods */ -bool RWSStateMachineInterface::Services::SG::getSettings(const std::string& task, SGSettings* p_settings) const +void RWSStateMachineInterface::Services::SG::getSettings(const std::string& task, SGSettings* p_settings) const { - return p_rws_interface_->getRAPIDSymbolData(task, Symbols::SG_SETTINGS, p_settings); + p_rws_interface_->getRAPIDSymbolData(task, Symbols::SG_SETTINGS, *p_settings); } -bool RWSStateMachineInterface::Services::SG::setCommandInput(const std::string& task, const SGCommands& command) const +void RWSStateMachineInterface::Services::SG::setCommandInput(const std::string& task, const SGCommands& command) const { RAPIDNum temp_command(command); - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_COMMAND_INPUT, temp_command); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_COMMAND_INPUT, temp_command); } -bool RWSStateMachineInterface::Services::SG::setSettings(const std::string& task, const SGSettings& settings) const +void RWSStateMachineInterface::Services::SG::setSettings(const std::string& task, const SGSettings& settings) const { - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_SETTINGS, settings); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_SETTINGS, settings); } -bool RWSStateMachineInterface::Services::SG::setTargetPositionInput(const std::string& task, const float position) const +void RWSStateMachineInterface::Services::SG::setTargetPositionInput(const std::string& task, const float position) const { RAPIDNum temp_position(position); - return p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_TARGET_POSTION_INPUT, temp_position); + p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_TARGET_POSTION_INPUT, temp_position); } @@ -690,15 +664,15 @@ bool RWSStateMachineInterface::Services::SG::setTargetPositionInput(const std::s * Primary methods */ -bool RWSStateMachineInterface::Services::Utility::getBaseFrame(const std::string& task, Pose* p_base_frame) const +void RWSStateMachineInterface::Services::Utility::getBaseFrame(const std::string& task, Pose* p_base_frame) const { - return p_rws_interface_->getRAPIDSymbolData(task, Symbols::UTILITY_BASE_FRAME, p_base_frame); + p_rws_interface_->getRAPIDSymbolData(task, Symbols::UTILITY_BASE_FRAME, *p_base_frame); } -bool RWSStateMachineInterface::Services::Utility::getCalibrationTarget(const std::string& task, +void RWSStateMachineInterface::Services::Utility::getCalibrationTarget(const std::string& task, JointTarget* p_calibration_joint_target) const { - return p_rws_interface_->getRAPIDSymbolData(task, Symbols::UTILITY_CALIBRATION_TARGET, p_calibration_joint_target); + p_rws_interface_->getRAPIDSymbolData(task, Symbols::UTILITY_CALIBRATION_TARGET, *p_calibration_joint_target); } @@ -712,40 +686,30 @@ bool RWSStateMachineInterface::Services::Utility::getCalibrationTarget(const std * Primary methods */ -TriBool RWSStateMachineInterface::Services::Watchdog::isActive(const std::string& task) const +bool RWSStateMachineInterface::Services::Watchdog::isActive(const std::string& task) const { - TriBool result; RAPIDBool temp_active; + p_rws_interface_->getRAPIDSymbolData(task, Symbols::WATCHDOG_ACTIVE, temp_active); - if (p_rws_interface_->getRAPIDSymbolData(task, Symbols::WATCHDOG_ACTIVE, &temp_active)) - { - result = temp_active.value; - } - - return result; + return temp_active; } -TriBool RWSStateMachineInterface::Services::Watchdog::isCheckingExternalStatus(const std::string& task) const +bool RWSStateMachineInterface::Services::Watchdog::isCheckingExternalStatus(const std::string& task) const { - TriBool result; RAPIDBool temp_check_external_status; + p_rws_interface_->getRAPIDSymbolData(task, Symbols::WATCHDOG_CHECK_EXTERNAL_STATUS, temp_check_external_status); - if (p_rws_interface_->getRAPIDSymbolData(task, Symbols::WATCHDOG_CHECK_EXTERNAL_STATUS, &temp_check_external_status)) - { - result = temp_check_external_status.value; - } - - return result; + return temp_check_external_status; } -bool RWSStateMachineInterface::Services::Watchdog::setExternalStatusSignal() const +void RWSStateMachineInterface::Services::Watchdog::setExternalStatusSignal() const { - return p_rws_interface_->setIOSignal(IOSignals::WD_EXTERNAL_STATUS, SystemConstants::IOSignals::HIGH); + p_rws_interface_->setIOSignal(IOSignals::WD_EXTERNAL_STATUS, SystemConstants::IOSignals::HIGH); } -bool RWSStateMachineInterface::Services::Watchdog::signalStopRequest() const +void RWSStateMachineInterface::Services::Watchdog::signalStopRequest() const { - return p_rws_interface_->toggleIOSignal(IOSignals::WD_STOP_REQUEST); + p_rws_interface_->toggleIOSignal(IOSignals::WD_STOP_REQUEST); } @@ -759,20 +723,17 @@ bool RWSStateMachineInterface::Services::Watchdog::signalStopRequest() const * Auxiliary methods */ -bool RWSStateMachineInterface::toggleIOSignal(const std::string& iosignal) +void RWSStateMachineInterface::toggleIOSignal(const std::string& iosignal) { bool result = false; int max_number_of_attempts = 5; - if (isAutoMode().isTrue()) + if (isAutoMode()) { for (int i = 0; i < max_number_of_attempts && !result; ++i) { - result = setIOSignal(iosignal, SystemConstants::IOSignals::LOW); - if (result) - { - result = (getIOSignal(iosignal) == SystemConstants::IOSignals::LOW); - } + setIOSignal(iosignal, SystemConstants::IOSignals::LOW); + result = (getIOSignal(iosignal) == SystemConstants::IOSignals::LOW); } if (result) @@ -781,16 +742,14 @@ bool RWSStateMachineInterface::toggleIOSignal(const std::string& iosignal) for (int i = 0; i < max_number_of_attempts && !result; ++i) { - result = setIOSignal(iosignal, SystemConstants::IOSignals::HIGH); - if (result) - { - result = (getIOSignal(iosignal) == SystemConstants::IOSignals::HIGH); - } + setIOSignal(iosignal, SystemConstants::IOSignals::HIGH); + result = (getIOSignal(iosignal) == SystemConstants::IOSignals::HIGH); } } } - return result; + if (!result) + throw std::runtime_error("RWSStateMachineInterface::toggleIOSignal() failed"); } } // end namespace rws diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index 34c6b5c5..e41a806c 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -73,10 +73,25 @@ namespace abb :: rws // Make a subscription request. POCOResult const poco_result = client_.httpPost(Services::SUBSCRIPTION, subscription_content.str()); - if (poco_result.poco_info.http.response.status != HTTPResponse::HTTP_CREATED) - throw std::runtime_error("Unable to create Subscription: " + poco_result.poco_info.http.response.content); + if (poco_result.httpStatus() != HTTPResponse::HTTP_CREATED) + throw std::runtime_error("Unable to create Subscription: " + poco_result.content()); - subscription_group_id_ = findSubstringContent(poco_result.poco_info.http.response.header_info, "/poll/", "\n"); + // Find "Location" header attribute + auto const h = std::find_if( + poco_result.headerInfo().begin(), poco_result.headerInfo().end(), + [] (auto const& p) { return p.first == "Location"; }); + + if (h != poco_result.headerInfo().end()) + { + std::string const poll = "/poll/"; + auto const start_postion = h->second.find(poll); + + if (start_postion != std::string::npos) + subscription_group_id_ = h->second.substr(start_postion + poll.size()); + } + + if (subscription_group_id_.empty()) + throw std::runtime_error("Cannot get subscription group from HTTP response"); } From f90b380f552c06b45bd5b48ad8e69efce8acae95 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82?= Date: Thu, 11 Feb 2021 10:44:55 +0100 Subject: [PATCH 15/17] Fix file path for loading modules (#2) * Fix file path for loading modules * Add comment --- src/rws_client.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 6c2613d3..2074f455 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -478,7 +478,11 @@ RWSResult RWSClient::setSpeedRatio(unsigned int ratio) RWSResult RWSClient::loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace) { std::string uri = generateRAPIDTasksPath(task) + "?" + Queries::ACTION_LOAD_MODULE; - std::string content = Identifiers::MODULEPATH + "=" + generateFilePath(resource) + "&replace=" + ((replace) ? "true" : "false"); + + // Path to file should be a direct path, i.e. without "/fileservice/" + std::string content = + Identifiers::MODULEPATH + "=" + resource.directory + "/" + resource.filename + + "&replace=" + ((replace) ? "true" : "false"); EvaluationConditions evaluation_conditions; evaluation_conditions.parse_message_into_xml = false; From 3936ef9f6fe13fe3875fdccd550dc41a66e109dc Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Tue, 16 Feb 2021 17:47:28 +0100 Subject: [PATCH 16/17] Fixed some issues pointed by code reviewer @Wojcik98 --- include/abb_librws/rws_client.h | 78 ++++++++++++++++++- include/abb_librws/rws_interface.h | 62 ++++++++++++++- .../abb_librws/rws_state_machine_interface.h | 2 - src/rws_client.cpp | 15 +--- src/rws_interface.cpp | 32 +++----- src/rws_subscription.cpp | 1 - 6 files changed, 148 insertions(+), 42 deletions(-) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index 7032058f..a4cd5e17 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -89,6 +89,8 @@ class RWSClient : public POCOClient * \brief A constructor. * * \param ip_address specifying the robot controller's IP address. + * + * \throw \a std::exception if something goes wrong. */ RWSClient(const std::string& ip_address) : @@ -104,6 +106,8 @@ class RWSClient : public POCOClient * \param ip_address specifying the robot controller's IP address. * \param username for the username to the RWS authentication process. * \param password for the password to the RWS authentication process. + * + * \throw \a std::exception if something goes wrong. */ RWSClient(const std::string& ip_address, const std::string& username, const std::string& password) : @@ -118,6 +122,8 @@ class RWSClient : public POCOClient * * \param ip_address specifying the robot controller's IP address. * \param port for the port used by the RWS server. + * + * \throw \a std::exception if something goes wrong. */ RWSClient(const std::string& ip_address, const unsigned short port) : @@ -134,6 +140,8 @@ class RWSClient : public POCOClient * \param port for the port used by the RWS server. * \param username for the username to the RWS authentication process. * \param password for the password to the RWS authentication process. + * + * \throw \a std::exception if something goes wrong. */ RWSClient(const std::string& ip_address, const unsigned short port, @@ -155,6 +163,8 @@ class RWSClient : public POCOClient * \brief Retrieves a list of controller resources (e.g. controller identity and clock information). * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getContollerService(); @@ -165,6 +175,8 @@ class RWSClient : public POCOClient * \param type specifying the type in the configuration topic. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getConfigurationInstances(const std::string& topic, const std::string& type); @@ -172,6 +184,8 @@ class RWSClient : public POCOClient * \brief A method for retrieving all available IO signals on the controller. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getIOSignals(); @@ -181,6 +195,8 @@ class RWSClient : public POCOClient * \param iosignal for the IO signal's name. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getIOSignal(const std::string& iosignal); @@ -190,6 +206,8 @@ class RWSClient : public POCOClient * \param mechunit for the mechanical unit's name. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getMechanicalUnitStaticInfo(const std::string& mechunit); @@ -199,6 +217,8 @@ class RWSClient : public POCOClient * \param mechunit for the mechanical unit's name. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getMechanicalUnitDynamicInfo(const std::string& mechunit); @@ -208,6 +228,8 @@ class RWSClient : public POCOClient * \param mechunit for the mechanical unit's name. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getMechanicalUnitJointTarget(const std::string& mechunit); @@ -220,6 +242,8 @@ class RWSClient : public POCOClient * \param wobj for the work object (wobj) relative to which the robtarget will be reported. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getMechanicalUnitRobTarget(const std::string& mechunit, const Coordinate& coordinate = Coordinate::ACTIVE, @@ -232,6 +256,8 @@ class RWSClient : public POCOClient * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getRAPIDSymbolData(const RAPIDResource& resource); @@ -240,6 +266,8 @@ class RWSClient : public POCOClient * * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. * \param data for containing the retrieved data. + * + * \throw \a std::exception if something goes wrong. */ void getRAPIDSymbolData(const RAPIDResource& resource, RAPIDSymbolDataAbstract& data); @@ -249,6 +277,8 @@ class RWSClient : public POCOClient * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getRAPIDSymbolProperties(const RAPIDResource& resource); @@ -256,6 +286,8 @@ class RWSClient : public POCOClient * \brief A method for retrieving the execution state of RAPID. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getRAPIDExecution(); @@ -265,6 +297,8 @@ class RWSClient : public POCOClient * \param task specifying the RAPID task. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getRAPIDModulesInfo(const std::string& task); @@ -272,6 +306,8 @@ class RWSClient : public POCOClient * \brief A method for retrieving the RAPID tasks that are defined in the robot controller system. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getRAPIDTasks(); @@ -279,6 +315,8 @@ class RWSClient : public POCOClient * \brief A method for retrieving info about the current robot controller system. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getRobotWareSystem(); @@ -286,6 +324,8 @@ class RWSClient : public POCOClient * \brief A method for retrieving the robot controller's speed ratio for RAPID motions (e.g. MoveJ and MoveL). * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getSpeedRatio(); @@ -293,6 +333,8 @@ class RWSClient : public POCOClient * \brief A method for retrieving the controller state. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getPanelControllerState(); @@ -300,6 +342,8 @@ class RWSClient : public POCOClient * \brief A method for retrieving the operation mode of the controller. * * \return RWSResult containing the result. + * + * \throw \a std::exception if something goes wrong. */ RWSResult getPanelOperationMode(); @@ -308,6 +352,8 @@ class RWSClient : public POCOClient * * \param iosignal for the IO signal's name. * \param value for the IO signal's new value. + * + * \throw \a std::exception if something goes wrong. */ void setIOSignal(const std::string& iosignal, const std::string& value); @@ -316,6 +362,8 @@ class RWSClient : public POCOClient * * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. * \param data for the RAPID symbol's new data. + * + * \throw \a std::exception if something goes wrong. */ void setRAPIDSymbolData(const RAPIDResource& resource, const std::string& data); @@ -324,31 +372,43 @@ class RWSClient : public POCOClient * * \param resource specifying the RAPID task, module and symbol names for the RAPID resource. * \param data for the RAPID symbol's new data. + * + * \throw \a std::exception if something goes wrong. */ void setRAPIDSymbolData(const RAPIDResource& resource, const RAPIDSymbolDataAbstract& data); /** * \brief A method for starting RAPID execution in the robot controller. + * + * \throw \a std::exception if something goes wrong. */ void startRAPIDExecution(); /** * \brief A method for stopping RAPID execution in the robot controller. + * + * \throw \a std::exception if something goes wrong. */ void stopRAPIDExecution(); /** * \brief A method for reseting the RAPID program pointer in the robot controller. + * + * \throw \a std::exception if something goes wrong. */ void resetRAPIDProgramPointer(); /** * \brief A method for turning on the robot controller's motors. + * + * \throw \a std::exception if something goes wrong. */ void setMotorsOn(); /** * \brief A method for turning off the robot controller's motors. + * + * \throw \a std::exception if something goes wrong. */ void setMotorsOff(); @@ -363,6 +423,8 @@ class RWSClient : public POCOClient * * \throw std::out_of_range if argument is out of range. * \throw std::runtime_error if failed to create a string from the argument. + * + * \throw \a std::exception if something goes wrong. */ void setSpeedRatio(unsigned int ratio); @@ -373,7 +435,7 @@ class RWSClient : public POCOClient * \param resource specifying the file's directory and name. * \param replace indicating if the actual module into the controller must be replaced by the new one or not. * - * \throw std::exception if something goes wrong. + * \throw \a std::exception if something goes wrong. */ void loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace = false); @@ -383,7 +445,7 @@ class RWSClient : public POCOClient * \param task specifying the RAPID task. * \param resource specifying the file's directory and name. * - * \throw std::exception if something goes wrong. + * \throw \a std::exception if something goes wrong. */ void unloadModuleFromTask(const std::string& task, const FileResource& resource); @@ -394,6 +456,8 @@ class RWSClient : public POCOClient * * \param resource specifying the file's directory and name. * \param p_file_content for containing the retrieved file content. + * + * \throw \a std::exception if something goes wrong. */ void getFile(const FileResource& resource, std::string* p_file_content); @@ -402,6 +466,8 @@ class RWSClient : public POCOClient * * \param resource specifying the file's directory and name. * \param file_content for the file's content. + * + * \throw \a std::exception if something goes wrong. */ void uploadFile(const FileResource& resource, const std::string& file_content); @@ -409,6 +475,8 @@ class RWSClient : public POCOClient * \brief A method for deleting a file from the robot controller. * * \param resource specifying the file's directory and name. + * + * \throw \a std::exception if something goes wrong. */ void deleteFile(const FileResource& resource); @@ -419,6 +487,8 @@ class RWSClient : public POCOClient * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. + * + * \throw \a std::exception if something goes wrong. */ void registerLocalUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, @@ -430,6 +500,8 @@ class RWSClient : public POCOClient * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. + * + * \throw \a std::exception if something goes wrong. */ void registerRemoteUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, @@ -440,6 +512,8 @@ class RWSClient : public POCOClient * * \param result containing the result of the parsing. * \param poco_result containing the POCO result. + * + * \throw \a std::exception if something goes wrong. */ static void parseMessage(RWSResult& result, const POCOResult& poco_result); diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 32c5b173..b515b065 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -518,6 +518,8 @@ class RWSInterface * * \param mechunit for the mechanical unit's name. * \param static_info for storing the retrieved information. + * + * \throw \a std::runtime_error if something goes wrong. */ void getMechanicalUnitStaticInfo(const std::string& mechunit, MechanicalUnitStaticInfo& static_info); @@ -526,6 +528,8 @@ class RWSInterface * * \param mechunit for the mechanical unit's name. * \param dynamic_info for storing the retrieved information. + * + * \throw \a std::runtime_error if something goes wrong. */ void getMechanicalUnitDynamicInfo(const std::string& mechunit, MechanicalUnitDynamicInfo& dynamic_info); @@ -534,6 +538,8 @@ class RWSInterface * * \param mechunit for the mechanical unit's name. * \param p_jointtarget for storing the retrieved jointtarget data. + * + * \throw \a std::runtime_error if something goes wrong. */ void getMechanicalUnitJointTarget(const std::string& mechunit, JointTarget* p_jointtarget); @@ -545,6 +551,8 @@ class RWSInterface * \param coordinate for the coordinate mode (base, world, tool, or wobj) in which the robtarget will be reported. * \param tool for the tool frame relative to which the robtarget will be reported. * \param wobj for the work object (wobj) relative to which the robtarget will be reported. + * + * \throw \a std::runtime_error if something goes wrong. */ void getMechanicalUnitRobTarget(const std::string& mechunit, RobTarget* p_robtarget, @@ -562,6 +570,8 @@ class RWSInterface * \param name name of the RAPID symbol. * * \return std::string containing the data. Empty if not found. + * + * \throw \a std::runtime_error if something goes wrong. */ std::string getRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name); @@ -572,6 +582,8 @@ class RWSInterface * \param module for the name of the RAPID module containing the RAPID symbol. * \param name for the name of the RAPID symbol. * \param data for storing the retrieved RAPID symbol data. + * + * \throw \a std::runtime_error if something goes wrong. */ void getRAPIDSymbolData(const std::string& task, const std::string& module, @@ -584,6 +596,8 @@ class RWSInterface * \param task for the name of the RAPID task containing the RAPID symbol. * \param symbol indicating the RAPID symbol resource (name and module). * \param data for storing the retrieved RAPID symbol data. + * + * \throw \a std::runtime_error if something goes wrong. */ void getRAPIDSymbolData(const std::string& task, const RAPIDSymbolResource& symbol, @@ -593,6 +607,8 @@ class RWSInterface * \brief A method for retrieving information about the RAPID modules of a RAPID task defined in the robot controller. * * \return std::vector containing the RAPID modules information. + * + * \throw \a std::runtime_error if something goes wrong. */ std::vector getRAPIDModulesInfo(const std::string& task); @@ -600,6 +616,8 @@ class RWSInterface * \brief A method for retrieving information about the RAPID tasks defined in the robot controller. * * \return std::vector containing the RAPID tasks information. + * + * \throw \a std::runtime_error if something goes wrong. */ std::vector getRAPIDTasks(); @@ -616,6 +634,8 @@ class RWSInterface * \brief A method for retrieving some system information from the robot controller. * * \return SystemInfo containing the system information (info will be empty if e.g. a timeout occurred). + * + * \throw \a std::runtime_error if something goes wrong. */ SystemInfo getSystemInfo(); @@ -623,6 +643,8 @@ class RWSInterface * \brief A method for checking if the robot controller mode is in auto mode. * * \return if the mode is auto or not. + * + * \throw \a std::runtime_error if something goes wrong. */ bool isAutoMode(); @@ -630,6 +652,8 @@ class RWSInterface * \brief A method for checking if the motors are on. * * \return if the motors are on or not. + * + * \throw \a std::runtime_error if something goes wrong. */ bool isMotorsOn(); @@ -637,6 +661,8 @@ class RWSInterface * \brief A method for checking if RAPID is running. * * \return if RAPID is running or not. + * + * \throw \a std::runtime_error if something goes wrong. */ bool isRAPIDRunning(); @@ -645,6 +671,8 @@ class RWSInterface * * \param iosignal for the name of the IO signal. * \param value for the IO signal's new value. + * + * \throw \a std::runtime_error if something goes wrong. */ void setIOSignal(const std::string& iosignal, const std::string& value); @@ -670,6 +698,8 @@ class RWSInterface * \param module name of the RAPID module containing the RAPID symbol. * \param name the name of the RAPID symbol. * \param data containing the RAPID symbol's new data. + * + * \throw \a std::runtime_error if something goes wrong. */ void setRAPIDSymbolData(const std::string& task, const std::string& module, @@ -683,6 +713,8 @@ class RWSInterface * \param module for the name of the RAPID module containing the RAPID symbol. * \param name for the name of the RAPID symbol. * \param data containing the RAPID symbol's new data. + * + * \throw \a std::runtime_error if something goes wrong. */ void setRAPIDSymbolData(const std::string& task, const std::string& module, @@ -695,6 +727,8 @@ class RWSInterface * \param task for the name of the RAPID task containing the RAPID symbol. * \param symbol indicating the RAPID symbol resource (name and module). * \param data containing the RAPID symbol's new data. + * + * \throw \a std::runtime_error if something goes wrong. */ void setRAPIDSymbolData(const std::string& task, const RAPIDSymbolResource& symbol, @@ -702,26 +736,36 @@ class RWSInterface /** * \brief A method for starting RAPID execution in the robot controller. + * + * \throw \a std::runtime_error if something goes wrong. */ void startRAPIDExecution(); /** * \brief A method for stopping RAPID execution in the robot controller. + * + * \throw \a std::runtime_error if something goes wrong. */ void stopRAPIDExecution(); /** * \brief A method for reseting the RAPID program pointer in the robot controller. + * + * \throw \a std::runtime_error if something goes wrong. */ void resetRAPIDProgramPointer(); /** * \brief A method for turning on the robot controller's motors. + * + * \throw \a std::runtime_error if something goes wrong. */ void setMotorsOn(); /** * \brief A method for turning off the robot controller's motors. + * + * \throw \a std::runtime_error if something goes wrong. */ void setMotorsOff(); @@ -731,6 +775,8 @@ class RWSInterface * Note: The ratio must be an integer in the range [0, 100] (ie: inclusive). * * \param ratio specifying the new ratio. + * + * \throw \a std::runtime_error if something goes wrong. */ void setSpeedRatio(unsigned int ratio); @@ -741,7 +787,7 @@ class RWSInterface * \param resource specifying the file's directory and name. * \param replace indicating if the actual module into the controller must be replaced by the new one or not. * - * \throw std::exception if something goes wrong. + * \throw \a std::exception if something goes wrong. */ void loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace = false); @@ -751,7 +797,7 @@ class RWSInterface * \param task specifying the RAPID task. * \param resource specifying the file's directory and name. * - * \throw std::exception if something goes wrong. + * \throw \a std::exception if something goes wrong. */ void unloadModuleFromTask(const std::string& task, const FileResource& resource); @@ -762,6 +808,8 @@ class RWSInterface * * \param resource specifying the file's directory and name. * \param p_file_content for containing the retrieved file content. + * + * \throw \a std::exception if something goes wrong. */ void getFile(const FileResource& resource, std::string* p_file_content); @@ -770,6 +818,8 @@ class RWSInterface * * \param resource specifying the file's directory and name. * \param file_content for the file's content. + * + * \throw \a std::exception if something goes wrong. */ void uploadFile(const FileResource& resource, const std::string& file_content); @@ -777,6 +827,8 @@ class RWSInterface * \brief A method for deleting a file from the robot controller. * * \param resource specifying the file's directory and name. + * + * \throw \a std::exception if something goes wrong. */ void deleteFile(const FileResource& resource); @@ -787,7 +839,7 @@ class RWSInterface * * \return Newly created \a SubscriptionGroup for specified subscription resources. * - * \throw \a std::runtime_error if something goes wrong + * \throw \a std::exception if something goes wrong */ SubscriptionGroup openSubscription(const SubscriptionResources& resources); @@ -797,6 +849,8 @@ class RWSInterface * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. + * + * \throw \a std::exception if something goes wrong. */ void registerLocalUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, @@ -808,6 +862,8 @@ class RWSInterface * \param username specifying the user name. * \param application specifying the external application. * \param location specifying the location. + * + * \throw \a std::exception if something goes wrong. */ void registerRemoteUser(const std::string& username = SystemConstants::General::DEFAULT_USERNAME, const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, diff --git a/include/abb_librws/rws_state_machine_interface.h b/include/abb_librws/rws_state_machine_interface.h index 246682e0..13d25fda 100644 --- a/include/abb_librws/rws_state_machine_interface.h +++ b/include/abb_librws/rws_state_machine_interface.h @@ -1340,8 +1340,6 @@ class RWSStateMachineInterface : public RWSInterface /** * \brief Signal the StateMachine to run SmartGripper routine(s). - * - * \return void indicating if the signaling was successful or not. */ void signalRunSGRoutine() const; diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 08265f65..c69b6386 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -588,20 +588,7 @@ void RWSClient::checkAcceptedOutcomes(const POCOResult& poco_result, void RWSClient::parseMessage(RWSResult& result, const POCOResult& poco_result) { - std::stringstream ss; - - if (!poco_result.content().empty()) - { - ss << poco_result.content(); - } - else - { - // XML parsing: Missing message - throw std::logic_error("parseMessage(...): RWS response was empty"); - } - - Poco::XML::InputSource input_source(ss); - result = Poco::XML::DOMParser().parse(&input_source); + result = Poco::XML::DOMParser().parseString(poco_result.content()); } diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index 486ca3a1..ea11fc98 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -604,15 +604,11 @@ void RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, Mech axes_total >> static_info.axes_total; // Basic verification. - if(!static_info.task_name.empty() && - !static_info.is_integrated_unit.empty() && - !static_info.has_integrated_unit.empty() && - static_info.type != MechanicalUnitType::UNDEFINED && - !axes.fail() && !axes_total.fail()) - { - ; - } - else + if(static_info.task_name.empty() || + static_info.is_integrated_unit.empty() || + static_info.has_integrated_unit.empty() || + static_info.type == MechanicalUnitType::UNDEFINED || + axes.fail() || axes_total.fail()) { throw std::logic_error("RWSInterface::getMechanicalUnitStaticInfo(): inconsistent data"); } @@ -664,17 +660,13 @@ void RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, Mec } // Basic verification. - if(!dynamic_info.tool_name.empty() && - !dynamic_info.wobj_name.empty() && - !dynamic_info.payload_name.empty() && - !dynamic_info.total_payload_name.empty() && - !dynamic_info.status.empty() && - !dynamic_info.jog_mode.empty() && - dynamic_info.mode != MechanicalUnitMode::UNKNOWN_MODE) - { - ; - } - else + if(dynamic_info.tool_name.empty() || + dynamic_info.wobj_name.empty() || + dynamic_info.payload_name.empty() || + dynamic_info.total_payload_name.empty() || + dynamic_info.status.empty() || + dynamic_info.jog_mode.empty() || + dynamic_info.mode == MechanicalUnitMode::UNKNOWN_MODE) { throw std::logic_error("RWSInterface::getMechanicalUnitDynamicInfo: inconsistent data"); } diff --git a/src/rws_subscription.cpp b/src/rws_subscription.cpp index e41a806c..29220224 100644 --- a/src/rws_subscription.cpp +++ b/src/rws_subscription.cpp @@ -129,7 +129,6 @@ namespace abb :: rws WebSocketFrame frame; if (webSocketReceiveFrame(frame)) { - // std::clog << "WebSocket frame received: flags=" << frame.flags << ", frame_content=" << frame.frame_content << std::endl; Poco::AutoPtr doc = parser_.parseString(frame.frame_content); event.value = xmlFindTextContent(doc, XMLAttribute {"class", "lvalue"}); From 803aa501370d1172994b798e0dbd815cb853adf5 Mon Sep 17 00:00:00 2001 From: Mikhail Katliar Date: Fri, 19 Feb 2021 11:40:39 +0100 Subject: [PATCH 17/17] Improvements in RWSClient and RWSInterface class interfaces. --- include/abb_librws/rws_client.h | 5 +- include/abb_librws/rws_interface.h | 150 +++++++++++++----------- src/rws_client.cpp | 19 ++- src/rws_interface.cpp | 172 +++++++++++++++------------- src/rws_state_machine_interface.cpp | 52 ++++----- 5 files changed, 212 insertions(+), 186 deletions(-) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index a4cd5e17..6018435d 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -455,11 +455,12 @@ class RWSClient : public POCOClient * Note: Depending on the file, then the content can be in text or binary format. * * \param resource specifying the file's directory and name. - * \param p_file_content for containing the retrieved file content. + * + * \return retrieved file content. * * \throw \a std::exception if something goes wrong. */ - void getFile(const FileResource& resource, std::string* p_file_content); + std::string getFile(const FileResource& resource); /** * \brief A method for uploading a file to the robot controller. diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index b515b065..20e8b5a9 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -504,58 +504,69 @@ class RWSInterface */ ABB_LIBRWS_DEPRECATED std::vector getPresentRobotWareOptions(); - /** - * \brief A method for retrieving the value if an IO signal. - * - * \param iosignal for the name of the IO signal. - * - * \return std::string containing the IO signal's value (empty if not found). - */ - std::string getIOSignal(const std::string& iosignal); + + /// @brief Get value of a digital signal + /// + /// @param signal_name Name of the signal + /// @return Value of the requested digital signal + /// + bool getDigitalSignal(std::string const& signal_name); + + + /// @brief Get value of an analog signal + /// + /// @param signal_name Name of the signal + /// @return Value of the requested analog signal + /// + float getAnalogSignal(std::string const& signal_name); + /** * \brief A method for retrieving static information about a mechanical unit. * * \param mechunit for the mechanical unit's name. - * \param static_info for storing the retrieved information. + * + * \return static information about a mechanical unit. * * \throw \a std::runtime_error if something goes wrong. */ - void getMechanicalUnitStaticInfo(const std::string& mechunit, MechanicalUnitStaticInfo& static_info); + MechanicalUnitStaticInfo getMechanicalUnitStaticInfo(const std::string& mechunit); /** * \brief A method for retrieving dynamic information about a mechanical unit. * * \param mechunit for the mechanical unit's name. - * \param dynamic_info for storing the retrieved information. + * + * \return dynamic information about a mechanical unit. * * \throw \a std::runtime_error if something goes wrong. */ - void getMechanicalUnitDynamicInfo(const std::string& mechunit, MechanicalUnitDynamicInfo& dynamic_info); + MechanicalUnitDynamicInfo getMechanicalUnitDynamicInfo(const std::string& mechunit); /** * \brief A method for retrieving the current jointtarget values of a mechanical unit. * * \param mechunit for the mechanical unit's name. - * \param p_jointtarget for storing the retrieved jointtarget data. * + * \return jointtarget data. + * * \throw \a std::runtime_error if something goes wrong. */ - void getMechanicalUnitJointTarget(const std::string& mechunit, JointTarget* p_jointtarget); + JointTarget getMechanicalUnitJointTarget(const std::string& mechunit); /** * \brief A method for retrieving the current robtarget values of a mechanical unit. * * \param mechunit for the mechanical unit's name. - * \param p_robtarget for storing the retrieved robtarget data. * \param coordinate for the coordinate mode (base, world, tool, or wobj) in which the robtarget will be reported. * \param tool for the tool frame relative to which the robtarget will be reported. * \param wobj for the work object (wobj) relative to which the robtarget will be reported. * * \throw \a std::runtime_error if something goes wrong. + * + * \return robtarget data. */ - void getMechanicalUnitRobTarget(const std::string& mechunit, - RobTarget* p_robtarget, + RobTarget getMechanicalUnitRobTarget(const std::string& mechunit, Coordinate coordinate = Coordinate::ACTIVE, const std::string& tool = "", const std::string& wobj = ""); @@ -575,38 +586,22 @@ class RWSInterface */ std::string getRAPIDSymbolData(const std::string& task, const std::string& module, const std::string& name); - /** - * \brief A method for retrieving the data of a RAPID symbol (parsed into a struct representing the RAPID data). - * - * \param task for the name of the RAPID task containing the RAPID symbol. - * \param module for the name of the RAPID module containing the RAPID symbol. - * \param name for the name of the RAPID symbol. - * \param data for storing the retrieved RAPID symbol data. - * - * \throw \a std::runtime_error if something goes wrong. - */ - void getRAPIDSymbolData(const std::string& task, - const std::string& module, - const std::string& name, - RAPIDSymbolDataAbstract& data); /** - * \brief A method for retrieving the data of a RAPID symbol (parsed into a struct representing the RAPID data). - * - * \param task for the name of the RAPID task containing the RAPID symbol. - * \param symbol indicating the RAPID symbol resource (name and module). + * \brief Retrieves the data of a RAPID symbol (parsed into a struct representing the RAPID data). + * + * \param resource specifies the RAPID task, module and symbol name. * \param data for storing the retrieved RAPID symbol data. * * \throw \a std::runtime_error if something goes wrong. */ - void getRAPIDSymbolData(const std::string& task, - const RAPIDSymbolResource& symbol, - RAPIDSymbolDataAbstract& data); + void getRAPIDSymbolData(RAPIDResource const& resource, RAPIDSymbolDataAbstract& data); + /** * \brief A method for retrieving information about the RAPID modules of a RAPID task defined in the robot controller. * - * \return std::vector containing the RAPID modules information. + * \return \a std::vector containing the RAPID modules information. * * \throw \a std::runtime_error if something goes wrong. */ @@ -615,7 +610,7 @@ class RWSInterface /** * \brief A method for retrieving information about the RAPID tasks defined in the robot controller. * - * \return std::vector containing the RAPID tasks information. + * \return \a std::vector containing the RAPID tasks information. * * \throw \a std::runtime_error if something goes wrong. */ @@ -626,7 +621,7 @@ class RWSInterface * * \return unsigned int with the speed ratio in the range [0, 100] (ie: inclusive). * - * \throw std::runtime_error if failed to get or parse the speed ratio. + * \throw \a std::runtime_error if failed to get or parse the speed ratio. */ unsigned int getSpeedRatio(); @@ -666,15 +661,22 @@ class RWSInterface */ bool isRAPIDRunning(); - /** - * \brief A method for setting the value of an IO signal. - * - * \param iosignal for the name of the IO signal. - * \param value for the IO signal's new value. - * - * \throw \a std::runtime_error if something goes wrong. - */ - void setIOSignal(const std::string& iosignal, const std::string& value); + + /// @brief Set value of a digital signal + /// + /// @param signal_name Name of the signal + /// @param value New value of the signal + /// + void setDigitalSignal(std::string const& signal_name, bool value); + + + /// @brief Set value of an analog signal + /// + /// @param signal_name Name of the signal + /// @param value New value of the signal + /// + void setAnalogSignal(std::string const& signal_name, float value); + /** * \brief A method for setting the data of a RAPID symbol via raw text format. @@ -706,34 +708,19 @@ class RWSInterface const std::string& name, const std::string& data); - /** - * \brief A method for setting the data of a RAPID symbol. - * - * \param task for the name of the RAPID task containing the RAPID symbol. - * \param module for the name of the RAPID module containing the RAPID symbol. - * \param name for the name of the RAPID symbol. - * \param data containing the RAPID symbol's new data. - * - * \throw \a std::runtime_error if something goes wrong. - */ - void setRAPIDSymbolData(const std::string& task, - const std::string& module, - const std::string& name, - const RAPIDSymbolDataAbstract& data); /** * \brief A method for setting the data of a RAPID symbol. * - * \param task for the name of the RAPID task containing the RAPID symbol. - * \param symbol indicating the RAPID symbol resource (name and module). + * \param resource identifying the RAPID symbol. * \param data containing the RAPID symbol's new data. * * \throw \a std::runtime_error if something goes wrong. */ - void setRAPIDSymbolData(const std::string& task, - const RAPIDSymbolResource& symbol, + void setRAPIDSymbolData(RAPIDResource const& resource, const RAPIDSymbolDataAbstract& data); + /** * \brief A method for starting RAPID execution in the robot controller. * @@ -807,11 +794,12 @@ class RWSInterface * Note: Depending on the file, then the content can be in text or binary format. * * \param resource specifying the file's directory and name. - * \param p_file_content for containing the retrieved file content. + * + * \return file content. * * \throw \a std::exception if something goes wrong. */ - void getFile(const FileResource& resource, std::string* p_file_content); + std::string getFile(const FileResource& resource); /** * \brief A method for uploading a file to the robot controller. @@ -915,6 +903,28 @@ class RWSInterface * \brief The RWS client used to communicate with the robot controller. */ RWSClient rws_client_; + + +private: + /** + * \brief A method for retrieving the value if an IO signal. + * + * \param iosignal for the name of the IO signal. + * + * \return std::string containing the IO signal's value (empty if not found). + */ + std::string getIOSignal(const std::string& iosignal); + + + /** + * \brief A method for setting the value of an IO signal. + * + * \param iosignal for the name of the IO signal. + * \param value for the IO signal's new value. + * + * \throw \a std::runtime_error if something goes wrong. + */ + void setIOSignal(const std::string& iosignal, const std::string& value); }; } // end namespace rws diff --git a/src/rws_client.cpp b/src/rws_client.cpp index c69b6386..bb6315a7 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -468,20 +468,17 @@ void RWSClient::unloadModuleFromTask(const std::string& task, const FileResource evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -void RWSClient::getFile(const FileResource& resource, std::string* p_file_content) +std::string RWSClient::getFile(const FileResource& resource) { - if (p_file_content) - { - std::string uri = generateFilePath(resource); - POCOResult const poco_result = httpGet(uri); + std::string uri = generateFilePath(resource); + POCOResult const poco_result = httpGet(uri); - EvaluationConditions evaluation_conditions; - evaluation_conditions.parse_message_into_xml = false; - evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); + EvaluationConditions evaluation_conditions; + evaluation_conditions.parse_message_into_xml = false; + evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_OK); - evaluatePOCOResult(poco_result, evaluation_conditions); - *p_file_content = poco_result.content(); - } + evaluatePOCOResult(poco_result, evaluation_conditions); + return poco_result.content(); } void RWSClient::uploadFile(const FileResource& resource, const std::string& file_content) diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index ea11fc98..017a5ab4 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -566,10 +566,11 @@ std::string RWSInterface::getIOSignal(const std::string& iosignal) } -void RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, MechanicalUnitStaticInfo& static_info) +MechanicalUnitStaticInfo RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit) { RWSResult rws_result = rws_client_.getMechanicalUnitStaticInfo(mechunit); + MechanicalUnitStaticInfo static_info; static_info.task_name = xmlFindTextContent(rws_result, XMLAttribute("class", "task-name")); static_info.is_integrated_unit = xmlFindTextContent(rws_result, XMLAttribute("class", "is-integrated-unit")); @@ -612,14 +613,17 @@ void RWSInterface::getMechanicalUnitStaticInfo(const std::string& mechunit, Mech { throw std::logic_error("RWSInterface::getMechanicalUnitStaticInfo(): inconsistent data"); } + + return static_info; } -void RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, MechanicalUnitDynamicInfo& dynamic_info) +MechanicalUnitDynamicInfo RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit) { bool result = false; RWSResult rws_result = rws_client_.getMechanicalUnitDynamicInfo(mechunit); + MechanicalUnitDynamicInfo dynamic_info; dynamic_info.tool_name = xmlFindTextContent(rws_result, XMLAttribute("class", "tool-name")); dynamic_info.wobj_name = xmlFindTextContent(rws_result, XMLAttribute("class", "wobj-name")); dynamic_info.payload_name = xmlFindTextContent(rws_result, @@ -670,66 +674,67 @@ void RWSInterface::getMechanicalUnitDynamicInfo(const std::string& mechunit, Mec { throw std::logic_error("RWSInterface::getMechanicalUnitDynamicInfo: inconsistent data"); } + + return dynamic_info; } -void RWSInterface::getMechanicalUnitJointTarget(const std::string& mechunit, JointTarget* p_jointtarget) +JointTarget RWSInterface::getMechanicalUnitJointTarget(const std::string& mechunit) { - if (p_jointtarget) - { - RWSResult rws_result = rws_client_.getMechanicalUnitJointTarget(mechunit); - std::stringstream ss; - - ss << "[[" - << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_1")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_2")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_3")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_4")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_5")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_6")) << "], [" - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_a")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_b")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_c")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_d")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_e")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_f")) << "]]"; - - p_jointtarget->parseString(ss.str()); - } + RWSResult rws_result = rws_client_.getMechanicalUnitJointTarget(mechunit); + std::stringstream ss; + + ss << "[[" + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_1")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_2")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_3")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_4")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_5")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "rax_6")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_a")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_b")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_c")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_d")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_e")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_f")) << "]]"; + + JointTarget jointtarget; + jointtarget.parseString(ss.str()); + + return jointtarget; } -void RWSInterface::getMechanicalUnitRobTarget(const std::string& mechunit, - RobTarget* p_robtarget, +RobTarget RWSInterface::getMechanicalUnitRobTarget(const std::string& mechunit, Coordinate coordinate, const std::string& tool, const std::string& wobj) { - if (p_robtarget) - { - RWSResult rws_result = rws_client_.getMechanicalUnitRobTarget(mechunit, coordinate, tool, wobj); - - std::stringstream ss; - - ss << "[[" - << xmlFindTextContent(rws_result, XMLAttribute("class", "x")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "y")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "z")) << "], [" - << xmlFindTextContent(rws_result, XMLAttribute("class", "q1")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "q2")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "q3")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "q4")) << "], [" - << xmlFindTextContent(rws_result, XMLAttribute("class", "cf1")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "cf4")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "cf6")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "cfx")) << "], [" - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_a")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_b")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_c")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_d")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_e")) << "," - << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_f")) << "]]"; - - p_robtarget->parseString(ss.str()); - } + RWSResult rws_result = rws_client_.getMechanicalUnitRobTarget(mechunit, coordinate, tool, wobj); + + std::stringstream ss; + + ss << "[[" + << xmlFindTextContent(rws_result, XMLAttribute("class", "x")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "y")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "z")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "q1")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "q2")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "q3")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "q4")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "cf1")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "cf4")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "cf6")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "cfx")) << "], [" + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_a")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_b")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_c")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_d")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_e")) << "," + << xmlFindTextContent(rws_result, XMLAttribute("class", "eax_f")) << "]]"; + + RobTarget robtarget; + robtarget.parseString(ss.str()); + + return robtarget; } void RWSInterface::setRAPIDSymbolData(const std::string& task, @@ -740,21 +745,13 @@ void RWSInterface::setRAPIDSymbolData(const std::string& task, rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data); } -void RWSInterface::setRAPIDSymbolData(const std::string& task, - const std::string& module, - const std::string& name, - const RAPIDSymbolDataAbstract& data) -{ - rws_client_.setRAPIDSymbolData(RAPIDResource(task, module, name), data); -} -void RWSInterface::setRAPIDSymbolData(const std::string& task, - const RAPIDSymbolResource& symbol, - const RAPIDSymbolDataAbstract& data) +void RWSInterface::setRAPIDSymbolData(RAPIDResource const& resource, const RAPIDSymbolDataAbstract& data) { - rws_client_.setRAPIDSymbolData(RAPIDResource(task, symbol), data); + rws_client_.setRAPIDSymbolData(resource, data); } + void RWSInterface::startRAPIDExecution() { rws_client_.startRAPIDExecution(); @@ -916,21 +913,13 @@ std::string RWSInterface::getRAPIDSymbolData(const std::string& task, XMLAttributes::CLASS_VALUE); } -void RWSInterface::getRAPIDSymbolData(const std::string& task, - const std::string& module, - const std::string& name, - RAPIDSymbolDataAbstract& data) -{ - rws_client_.getRAPIDSymbolData(RAPIDResource(task, module, name), data); -} -void RWSInterface::getRAPIDSymbolData(const std::string& task, - const RAPIDSymbolResource& symbol, - RAPIDSymbolDataAbstract& data) +void RWSInterface::getRAPIDSymbolData(RAPIDResource const& resource, RAPIDSymbolDataAbstract& data) { - rws_client_.getRAPIDSymbolData(RAPIDResource(task, symbol), data); + rws_client_.getRAPIDSymbolData(resource, data); } + void RWSInterface::loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace) { rws_client_.loadModuleIntoTask(task, resource, replace); @@ -941,9 +930,9 @@ void RWSInterface::unloadModuleFromTask(const std::string& task, const FileResou rws_client_.unloadModuleFromTask(task, resource); } -void RWSInterface::getFile(const FileResource& resource, std::string* p_file_content) +std::string RWSInterface::getFile(const FileResource& resource) { - rws_client_.getFile(resource, p_file_content); + return rws_client_.getFile(resource); } void RWSInterface::uploadFile(const FileResource& resource, const std::string& file_content) @@ -985,6 +974,35 @@ std::string RWSInterface::getLogTextLatestEvent(const bool verbose) return rws_client_.getLogTextLatestEvent(verbose); } + +void RWSInterface::setDigitalSignal(std::string const& signal_name, bool value) +{ + setIOSignal(signal_name, std::string(value ? SystemConstants::IOSignals::HIGH : SystemConstants::IOSignals::LOW)); +} + + +void RWSInterface::setAnalogSignal(std::string const& signal_name, float value) +{ + setIOSignal(signal_name, std::to_string(value)); +} + + +bool RWSInterface::getDigitalSignal(std::string const& signal_name) +{ + auto const value = getIOSignal(signal_name); + + if (value != SystemConstants::IOSignals::HIGH && value != SystemConstants::IOSignals::LOW) + throw std::logic_error("Unexpected value \"" + value + "\" of a digital signal"); + + return value == SystemConstants::IOSignals::HIGH; +} + + +float RWSInterface::getAnalogSignal(std::string const& signal_name) +{ + return std::stof(getIOSignal(signal_name)); +} + /************************************************************ * Auxiliary methods */ diff --git a/src/rws_state_machine_interface.cpp b/src/rws_state_machine_interface.cpp index ffbbbbf1..4f66956e 100644 --- a/src/rws_state_machine_interface.cpp +++ b/src/rws_state_machine_interface.cpp @@ -111,7 +111,7 @@ EGMActions RWSStateMachineInterface::Services::EGM::getCurrentAction(const std:: EGMActions result; RAPIDNum temp_current_action; - p_rws_interface_->getRAPIDSymbolData(task, Symbols::EGM_CURRENT_ACTION, temp_current_action); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::EGM_CURRENT_ACTION}, temp_current_action); switch ((int) temp_current_action.value) { @@ -137,12 +137,12 @@ EGMActions RWSStateMachineInterface::Services::EGM::getCurrentAction(const std:: void RWSStateMachineInterface::Services::EGM::getSettings(const std::string& task, EGMSettings* p_settings) const { - p_rws_interface_->getRAPIDSymbolData(task, Symbols::EGM_SETTINGS, *p_settings); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::EGM_SETTINGS}, *p_settings); } void RWSStateMachineInterface::Services::EGM::setSettings(const std::string& task, const EGMSettings& settings) const { - p_rws_interface_->setRAPIDSymbolData(task, Symbols::EGM_SETTINGS, settings); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::EGM_SETTINGS}, settings); } void RWSStateMachineInterface::Services::EGM::signalEGMStartJoint() const @@ -185,7 +185,7 @@ States RWSStateMachineInterface::Services::Main::getCurrentState(const std::stri { States result = STATE_UNKNOWN; RAPIDNum temp_current_state; - p_rws_interface_->getRAPIDSymbolData(task, Symbols::MAIN_CURRENT_STATE, temp_current_state); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::MAIN_CURRENT_STATE}, temp_current_state); switch (static_cast(temp_current_state.value)) { @@ -218,7 +218,7 @@ bool RWSStateMachineInterface::Services::Main::isStateIdle(const std::string& ta bool RWSStateMachineInterface::Services::Main::isStationary(const std::string& mechanical_unit) const { - return p_rws_interface_->getIOSignal(IOSignals::OUTPUT_STATIONARY + "_" + mechanical_unit) == SystemConstants::IOSignals::HIGH; + return p_rws_interface_->getDigitalSignal(IOSignals::OUTPUT_STATIONARY + "_" + mechanical_unit); } @@ -238,8 +238,8 @@ void RWSStateMachineInterface::Services::RAPID::runCallByVar(const std::string& { RAPIDString temp_routine_name(routine_name); RAPIDNum temp_routine_number(routine_number); - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_CALL_BY_VAR_NAME_INPUT, temp_routine_name); - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_CALL_BY_VAR_NUM_INPUT, temp_routine_number); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_CALL_BY_VAR_NAME_INPUT}, temp_routine_name); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_CALL_BY_VAR_NUM_INPUT}, temp_routine_number); setRoutineName(task, Procedures::RUN_CALL_BY_VAR); signalRunRAPIDRoutine(); } @@ -248,7 +248,7 @@ void RWSStateMachineInterface::Services::RAPID::runModuleLoad(const std::string& const std::string& file_path) const { RAPIDString temp_file_path(file_path); - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MODULE_FILE_PATH_INPUT, temp_file_path); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_MODULE_FILE_PATH_INPUT}, temp_file_path); setRoutineName(task, Procedures::RUN_MODULE_LOAD); signalRunRAPIDRoutine(); } @@ -257,7 +257,7 @@ void RWSStateMachineInterface::Services::RAPID::runModuleUnload(const std::strin const std::string& file_path) const { RAPIDString temp_file_path(file_path); - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MODULE_FILE_PATH_INPUT, temp_file_path); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_MODULE_FILE_PATH_INPUT}, temp_file_path); setRoutineName(task, Procedures::RUN_MODULE_UNLOAD); signalRunRAPIDRoutine(); } @@ -265,14 +265,14 @@ void RWSStateMachineInterface::Services::RAPID::runModuleUnload(const std::strin void RWSStateMachineInterface::Services::RAPID::runMoveAbsJ(const std::string& task, const JointTarget& joint_target) const { - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_JOINT_TARGET_INPUT, joint_target); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_MOVE_JOINT_TARGET_INPUT}, joint_target); setRoutineName(task, Procedures::RUN_MOVE_ABS_J); signalRunRAPIDRoutine(); } void RWSStateMachineInterface::Services::RAPID::runMoveJ(const std::string& task, const RobTarget& rob_target) const { - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_ROB_TARGET_INPUT, rob_target); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_MOVE_ROB_TARGET_INPUT}, rob_target); setRoutineName(task, Procedures::RUN_MOVE_J); signalRunRAPIDRoutine(); } @@ -285,14 +285,14 @@ void RWSStateMachineInterface::Services::RAPID::runMoveToCalibrationPosition(con void RWSStateMachineInterface::Services::RAPID::setMoveSpeed(const std::string& task, const SpeedData& speed_data) const { - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_MOVE_SPEED_INPUT, speed_data); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_MOVE_SPEED_INPUT}, speed_data); } void RWSStateMachineInterface::Services::RAPID::setRoutineName(const std::string& task, const std::string& routine_name) const { RAPIDString temp_routine_name(routine_name); - p_rws_interface_->setRAPIDSymbolData(task, Symbols::RAPID_ROUTINE_NAME_INPUT, temp_routine_name); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::RAPID_ROUTINE_NAME_INPUT}, temp_routine_name); } void RWSStateMachineInterface::Services::RAPID::signalRunRAPIDRoutine() const @@ -633,24 +633,24 @@ void RWSStateMachineInterface::Services::SG::signalRunSGRoutine() const void RWSStateMachineInterface::Services::SG::getSettings(const std::string& task, SGSettings* p_settings) const { - p_rws_interface_->getRAPIDSymbolData(task, Symbols::SG_SETTINGS, *p_settings); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::SG_SETTINGS}, *p_settings); } void RWSStateMachineInterface::Services::SG::setCommandInput(const std::string& task, const SGCommands& command) const { RAPIDNum temp_command(command); - p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_COMMAND_INPUT, temp_command); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::SG_COMMAND_INPUT}, temp_command); } void RWSStateMachineInterface::Services::SG::setSettings(const std::string& task, const SGSettings& settings) const { - p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_SETTINGS, settings); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::SG_SETTINGS}, settings); } void RWSStateMachineInterface::Services::SG::setTargetPositionInput(const std::string& task, const float position) const { RAPIDNum temp_position(position); - p_rws_interface_->setRAPIDSymbolData(task, Symbols::SG_TARGET_POSTION_INPUT, temp_position); + p_rws_interface_->setRAPIDSymbolData({task, Symbols::SG_TARGET_POSTION_INPUT}, temp_position); } @@ -666,13 +666,13 @@ void RWSStateMachineInterface::Services::SG::setTargetPositionInput(const std::s void RWSStateMachineInterface::Services::Utility::getBaseFrame(const std::string& task, Pose* p_base_frame) const { - p_rws_interface_->getRAPIDSymbolData(task, Symbols::UTILITY_BASE_FRAME, *p_base_frame); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::UTILITY_BASE_FRAME}, *p_base_frame); } void RWSStateMachineInterface::Services::Utility::getCalibrationTarget(const std::string& task, JointTarget* p_calibration_joint_target) const { - p_rws_interface_->getRAPIDSymbolData(task, Symbols::UTILITY_CALIBRATION_TARGET, *p_calibration_joint_target); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::UTILITY_CALIBRATION_TARGET}, *p_calibration_joint_target); } @@ -689,7 +689,7 @@ void RWSStateMachineInterface::Services::Utility::getCalibrationTarget(const std bool RWSStateMachineInterface::Services::Watchdog::isActive(const std::string& task) const { RAPIDBool temp_active; - p_rws_interface_->getRAPIDSymbolData(task, Symbols::WATCHDOG_ACTIVE, temp_active); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::WATCHDOG_ACTIVE}, temp_active); return temp_active; } @@ -697,14 +697,14 @@ bool RWSStateMachineInterface::Services::Watchdog::isActive(const std::string& t bool RWSStateMachineInterface::Services::Watchdog::isCheckingExternalStatus(const std::string& task) const { RAPIDBool temp_check_external_status; - p_rws_interface_->getRAPIDSymbolData(task, Symbols::WATCHDOG_CHECK_EXTERNAL_STATUS, temp_check_external_status); + p_rws_interface_->getRAPIDSymbolData({task, Symbols::WATCHDOG_CHECK_EXTERNAL_STATUS}, temp_check_external_status); return temp_check_external_status; } void RWSStateMachineInterface::Services::Watchdog::setExternalStatusSignal() const { - p_rws_interface_->setIOSignal(IOSignals::WD_EXTERNAL_STATUS, SystemConstants::IOSignals::HIGH); + p_rws_interface_->setDigitalSignal(IOSignals::WD_EXTERNAL_STATUS, true); } void RWSStateMachineInterface::Services::Watchdog::signalStopRequest() const @@ -732,8 +732,8 @@ void RWSStateMachineInterface::toggleIOSignal(const std::string& iosignal) { for (int i = 0; i < max_number_of_attempts && !result; ++i) { - setIOSignal(iosignal, SystemConstants::IOSignals::LOW); - result = (getIOSignal(iosignal) == SystemConstants::IOSignals::LOW); + setDigitalSignal(iosignal, false); + result = !getDigitalSignal(iosignal); } if (result) @@ -742,8 +742,8 @@ void RWSStateMachineInterface::toggleIOSignal(const std::string& iosignal) for (int i = 0; i < max_number_of_attempts && !result; ++i) { - setIOSignal(iosignal, SystemConstants::IOSignals::HIGH); - result = (getIOSignal(iosignal) == SystemConstants::IOSignals::HIGH); + setDigitalSignal(iosignal, true); + result = getDigitalSignal(iosignal); } } }