From 7b732fdcb989a882a3aea65e891b8b9f917b337f Mon Sep 17 00:00:00 2001 From: dorianleveque Date: Mon, 23 Nov 2020 11:01:03 +0100 Subject: [PATCH 1/3] 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 2/3] 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 a04cfa967a844cb9358e87e8bcf31f6612d447a9 Mon Sep 17 00:00:00 2001 From: dorianleveque Date: Mon, 23 Nov 2020 11:55:03 +0100 Subject: [PATCH 3/3] load program methods added --- include/abb_librws/rws_client.h | 20 ++++++++++++++------ include/abb_librws/rws_common.h | 28 ++++++++++++++-------------- include/abb_librws/rws_interface.h | 13 ++++++------- src/rws_client.cpp | 19 ++++++++++++------- src/rws_common.cpp | 8 ++++---- src/rws_interface.cpp | 8 ++++---- 6 files changed, 54 insertions(+), 42 deletions(-) diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index 122ac3d4..2c92f61b 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -593,25 +593,24 @@ class RWSClient : public POCOClient RWSResult setSpeedRatio(unsigned int ratio); /** - * \brief A method for loading a module to the robot controller. + * \brief A method for loading a program 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 replace indicating if the actual program into the controller must be replaced by the new one or not. * * \return RWSResult containing the result. */ - RWSResult loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace = false); + RWSResult loadProgramIntoTask(const std::string& task, const FileResource& resource, const bool replace = false); /** - * \brief A method for unloading a module to the robot controller. + * \brief A method for unloading a program to the robot controller. * * \param task specifying the RAPID task. - * \param resource specifying the file's directory and name. * * \return RWSResult containing the result. */ - RWSResult unloadModuleFromTask(const std::string& task, const FileResource& resource); + RWSResult unloadProgramFromTask(const std::string& task); /** * \brief A method for retrieving a file from the robot controller. @@ -854,6 +853,15 @@ class RWSClient : public POCOClient * \return std::string containing the path. */ std::string generateRAPIDTasksPath(const std::string& task); + + /** + * \brief Method for generating a task program resource URI path. + * + * \param task for the task name. + * + * \return std::string containing the path. + */ + std::string generateRAPIDTasksProgramPath(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 fb93f137..064d5b64 100644 --- a/include/abb_librws/rws_common.h +++ b/include/abb_librws/rws_common.h @@ -598,16 +598,6 @@ 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. */ @@ -633,6 +623,11 @@ struct SystemConstants */ static const std::string PRESENT_OPTIONS; + /** + * \brief Program path. + */ + static const std::string PROGRAM_PATH; + /** * \brief RAPID module info list item. */ @@ -705,9 +700,9 @@ struct SystemConstants struct ABB_LIBRWS_EXPORT Queries { /** - * \brief Load module action query. + * \brief Load program action query. */ - static const std::string ACTION_LOAD_MODULE; + static const std::string ACTION_LOAD_PROGRAM; /** * \brief Release action query. @@ -750,9 +745,9 @@ struct SystemConstants static const std::string ACTION_STOP; /** - * \brief Unload module action query. + * \brief Unload program action query. */ - static const std::string ACTION_UNLOAD_MODULE; + static const std::string ACTION_UNLOAD_PROGRAM; /** * \brief Task query. @@ -780,6 +775,11 @@ struct SystemConstants */ static const std::string LOGOUT; + /** + * \brief RAPID tasks program. + */ + static const std::string PROGRAM; + /** * \brief Robtarget. */ diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 74150769..2ffa0ba9 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -763,26 +763,25 @@ class RWSInterface bool setSpeedRatio(unsigned int ratio); /** - * \brief A method for loading a module to the robot controller. + * \brief A method for loading a program 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 replace indicating if the actual program into the controller must be replaced by the new one or not. * * \return bool indicating if the communication was successful or not. */ - bool loadModuleIntoTask(const std::string& task, const RWSClient::FileResource& resource, const bool replace = false); + bool loadProgramIntoTask(const std::string& task, const RWSClient::FileResource& resource, const bool replace = false); /** - * \brief A method for unloading a module to the robot controller. + * \brief A method for unloading a program to the robot controller. * * \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 unloadModuleFromTask(const std::string& task, const RWSClient::FileResource& resource); - + bool unloadProgramFromTask(const std::string& task); + /** * \brief A method for retrieving a file from the robot controller. * diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 2f43358a..8afc9dce 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -474,11 +474,11 @@ RWSClient::RWSResult RWSClient::setSpeedRatio(unsigned int ratio) return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::loadModuleIntoTask(const std::string& task, const FileResource& resource, const bool replace) +RWSClient::RWSResult RWSClient::loadProgramIntoTask(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"); - + std::string uri = generateRAPIDTasksProgramPath(task) + "?" + Queries::ACTION_LOAD_PROGRAM; + std::string content = Identifiers::PROGRAM_PATH + "=" + generateFilePath(resource) + "&loadmod=" + ((replace) ? "replace" : "add"); + EvaluationConditions evaluation_conditions; evaluation_conditions.parse_message_into_xml = false; evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_NO_CONTENT); @@ -486,10 +486,10 @@ RWSClient::RWSResult RWSClient::loadModuleIntoTask(const std::string& task, cons return evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); } -RWSClient::RWSResult RWSClient::unloadModuleFromTask(const std::string& task, const FileResource& resource) +RWSClient::RWSResult RWSClient::unloadProgramFromTask(const std::string& task) { - std::string uri = generateRAPIDTasksPath(task) + "?" + Queries::ACTION_UNLOAD_MODULE; - std::string content = Identifiers::MODULE + "=" + resource.filename; + std::string uri = generateRAPIDTasksProgramPath(task) + "?" + Queries::ACTION_UNLOAD_PROGRAM; + std::string content = ""; EvaluationConditions evaluation_conditions; evaluation_conditions.parse_message_into_xml = false; @@ -827,5 +827,10 @@ std::string RWSClient::generateRAPIDTasksPath(const std::string& task) return Resources::RW_RAPID_TASKS + "/" + task; } +std::string RWSClient::generateRAPIDTasksProgramPath(const std::string& task) +{ + return generateRAPIDTasksPath(task) + Resources::PROGRAM; +} + } // end namespace rws } // end namespace abb diff --git a/src/rws_common.cpp b/src/rws_common.cpp index 3c1f0bfe..4206ea6a 100644 --- a/src/rws_common.cpp +++ b/src/rws_common.cpp @@ -273,12 +273,11 @@ 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"; const std::string Identifiers::PRESENT_OPTIONS = "present_options"; +const std::string Identifiers::PROGRAM_PATH = "progpath"; const std::string Identifiers::RAP_MODULE_INFO_LI = "rap-module-info-li"; const std::string Identifiers::RAP_TASK_LI = "rap-task-li"; const std::string Identifiers::ROBOT = "robot"; @@ -293,7 +292,7 @@ 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_LOAD_PROGRAM = "action=loadprog"; const std::string Queries::ACTION_RELEASE = "action=release"; const std::string Queries::ACTION_REQUEST = "action=request"; const std::string Queries::ACTION_RESETPP = "action=resetpp"; @@ -302,7 +301,7 @@ const std::string Queries::ACTION_SETCTRLSTATE = "action=setctrls 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::ACTION_UNLOAD_MODULE = "action=unloadmod"; +const std::string Queries::ACTION_UNLOAD_PROGRAM = "action=unloadprog"; const std::string Queries::TASK = "task="; const std::string Services::CTRL = "/ctrl"; const std::string Services::FILESERVICE = "/fileservice"; @@ -312,6 +311,7 @@ const std::string Services::USERS = "/users"; const std::string Resources::INSTANCES = "/instances"; const std::string Resources::JOINTTARGET = "/jointtarget"; const std::string Resources::LOGOUT = "/logout"; +const std::string Resources::PROGRAM = "/program"; const std::string Resources::ROBTARGET = "/robtarget"; const std::string Resources::RW_CFG = Services::RW + "/cfg"; const std::string Resources::RW_IOSYSTEM_SIGNALS = Services::RW + "/iosystem/signals"; diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index 5a86635f..636599bd 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -978,14 +978,14 @@ bool RWSInterface::getRAPIDSymbolData(const std::string& task, return rws_client_.getRAPIDSymbolData(RWSClient::RAPIDResource(task, symbol), p_data).success; } -bool RWSInterface::loadModuleIntoTask(const std::string& task, const RWSClient::FileResource& resource, const bool replace) +bool RWSInterface::loadProgramIntoTask(const std::string& task, const RWSClient::FileResource& resource, const bool replace) { - return rws_client_.loadModuleIntoTask(task, resource, replace).success; + return rws_client_.loadProgramIntoTask(task, resource, replace).success; } -bool RWSInterface::unloadModuleFromTask(const std::string& task, const RWSClient::FileResource& resource) +bool RWSInterface::unloadProgramFromTask(const std::string &task) { - return rws_client_.unloadModuleFromTask(task, resource).success; + return rws_client_.unloadProgramFromTask(task).success; } bool RWSInterface::getFile(const RWSClient::FileResource& resource, std::string* p_file_content)