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;