From 9115a87793e95a6d706b8d1c7efdcea31ab861b6 Mon Sep 17 00:00:00 2001 From: Aris Synodinos Date: Fri, 11 Dec 2020 11:03:51 +0100 Subject: [PATCH 1/4] Added comparison operators for various datatypes in rws_interface and rws_cfg --- include/abb_librws/rws_cfg.h | 98 ++++++++++++++++++++++++++++++ include/abb_librws/rws_interface.h | 24 ++++++++ 2 files changed, 122 insertions(+) diff --git a/include/abb_librws/rws_cfg.h b/include/abb_librws/rws_cfg.h index 580e5ec4..05eea986 100644 --- a/include/abb_librws/rws_cfg.h +++ b/include/abb_librws/rws_cfg.h @@ -70,6 +70,19 @@ namespace moc */ struct Arm { + + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const Arm& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ @@ -96,6 +109,19 @@ struct Arm */ struct Joint { + + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const Joint& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ @@ -127,6 +153,18 @@ struct Joint */ struct MechanicalUnit { + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const MechanicalUnit& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ @@ -148,6 +186,18 @@ struct MechanicalUnit */ struct Robot { + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const Robot& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ @@ -179,6 +229,18 @@ struct Robot */ struct Single { + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const Single& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ @@ -210,6 +272,18 @@ struct Single */ struct Transmission { + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const Transmission& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ @@ -232,6 +306,18 @@ namespace sys */ struct MechanicalUnitGroup { + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const MechanicalUnitGroup& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ @@ -253,6 +339,18 @@ struct MechanicalUnitGroup */ struct PresentOption { + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const PresentOption& rhs) + { + return name == rhs.name; + } + /** * \brief The instance's name. */ diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 26806709..7b44f15e 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -241,6 +241,18 @@ class RWSInterface type(type) {} + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const RAPIDModuleInfo& rhs) + { + return name == rhs.name; + } + /** * \brief The module's name. */ @@ -276,6 +288,18 @@ class RWSInterface execution_state(execution_state) {} + /** + * \brief Operator for equal to comparison. + * + * \param rhs for right hand side value. + * + * \return bool indicating if the comparision was equal or not. + */ + bool operator==(const RAPIDTaskInfo& rhs) + { + return name == rhs.name; + } + /** * \brief The task's name. */ From 978452bb109b55aa84253e04b3302c0cc07adf5f Mon Sep 17 00:00:00 2001 From: Aris Synodinos Date: Fri, 11 Dec 2020 11:20:11 +0100 Subject: [PATCH 2/4] Added python wrapper for abb_rws --- CMakeLists.txt | 2 + python/CMakeLists.txt | 47 ++++ python/__init__.py | 45 +++ python/rws_interface_py.cpp | 544 ++++++++++++++++++++++++++++++++++++ test/test_python.py | 194 +++++++++++++ test/test_robot.mod | 24 ++ 6 files changed, 856 insertions(+) create mode 100644 python/CMakeLists.txt create mode 100644 python/__init__.py create mode 100644 python/rws_interface_py.cpp create mode 100755 test/test_python.py create mode 100644 test/test_robot.mod diff --git a/CMakeLists.txt b/CMakeLists.txt index f5abf195..d2e5454d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -125,3 +125,5 @@ install( FILE ${PROJECT_NAME}Targets.cmake NAMESPACE ${PROJECT_NAME}:: ) + +add_subdirectory(python) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt new file mode 100644 index 00000000..a32fc11b --- /dev/null +++ b/python/CMakeLists.txt @@ -0,0 +1,47 @@ +set(PYTHON_VERSIONS "2" "3") +foreach(PYTHON_VERSION ${PYTHON_VERSIONS}) + unset(PYTHON_EXECUTABLE CACHE) + unset(PYTHON_INCLUDE_DIR CACHE) + unset(PYTHON_LIBRARY CACHE) + unset(PYTHON_DEFAULT_EXECUTABLE CACHE) + find_package(PythonInterp ${PYTHON_VERSION}) + find_package(PythonLibs ${PYTHON_VERSION}) + + if(PYTHON_VERSION VERSION_LESS 3) + find_package(Boost COMPONENTS python) + else() + find_package(Boost COMPONENTS python-py${PYTHON_VERSION_MAJOR}${PYTHON_VERSION_MINOR}) + endif() + if (NOT Boost_FOUND) + message(WARNING "Boost was not found for python ${PYTHON_VERSION}") + continue() + endif() + + add_library(${PROJECT_NAME}_py${PYTHON_VERSION} rws_interface_py.cpp) + target_link_libraries(${PROJECT_NAME}_py${PYTHON_VERSION} + ${PROJECT_NAME} + ${Boost_LIBRARIES} + ${Poco_LIBRARIES} + ${PYTHON_LIBRARIES} + ) + target_include_directories(${PROJECT_NAME}_py${PYTHON_VERSION} PUBLIC + "$" + $/include> + ${Boost_INCLUDE_DIRS} + ${Poco_INCLUDE_DIRS} + ${PYTHON_INCLUDE_DIRS} + ) + set_target_properties(${PROJECT_NAME}_py${PYTHON_VERSION} + PROPERTIES + PREFIX "" + OUTPUT_NAME ${PROJECT_NAME}_py + LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/${PROJECT_NAME}_py${PYTHON_VERSION}/) + + install(TARGETS ${PROJECT_NAME}_py${PYTHON_VERSION} + DESTINATION "${CMAKE_INSTALL_LIBDIR}/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/dist-packages/${PROJECT_NAME}" + ) + + install(FILES __init__.py + DESTINATION "${CMAKE_INSTALL_LIBDIR}/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/dist-packages/${PROJECT_NAME}" + ) +endforeach() diff --git a/python/__init__.py b/python/__init__.py new file mode 100644 index 00000000..b24c266d --- /dev/null +++ b/python/__init__.py @@ -0,0 +1,45 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2020, Unibap AB (publ) +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Authors: Batu Akan, Aris Synodinos + +import sys, pkg_resources, imp + + +def __bootstrap__(): + global __bootstrap__, __loader__, __file__ + filepath = '../../../python{}.{}/dist-packages/abb_librws/abb_librws_py.so'.format(sys.version_info[0], sys.version_info[1]) + __file__ = pkg_resources.resource_filename(__name__, filepath) + __loader__ = None; del __bootstrap__, __loader__ + imp.load_dynamic(__name__,__file__) + +__bootstrap__() diff --git a/python/rws_interface_py.cpp b/python/rws_interface_py.cpp new file mode 100644 index 00000000..91d30c73 --- /dev/null +++ b/python/rws_interface_py.cpp @@ -0,0 +1,544 @@ +/*********************************************************************************************************************** + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, Unibap AB (publ) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with + * or without modification, are permitted provided that + * the following conditions are met: + * + * * Redistributions of source code must retain the + * above copyright notice, this list of conditions + * and the following disclaimer. + * * Redistributions in binary form must reproduce the + * above copyright notice, this list of conditions + * and the following disclaimer in the documentation + * and/or other materials provided with the + * distribution. + * * Neither the name of ABB nor the names of its + * contributors may be used to endorse or promote + * products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF + * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + *********************************************************************************************************************** + * + * Authors: Batu Akan, Aris Synodinos + * + */ + + +#include +#include + +#include "abb_librws/rws_interface.h" +#include "abb_librws/rws_rapid.h" + +#include + +#include + +using namespace abb::rws; + + +class PyRAPIDRecord : public RAPIDRecord +{ +public: + using RAPIDRecord::RAPIDRecord; + + void addComponents(RAPIDSymbolDataAbstract* data) + { + components_.push_back(data); + } +}; + + +class RWSInterfacePy : public RWSInterface +{ + using RWSInterface::RWSInterface; + public: + std::string waitForSubscriptionEventAsString() + { + RWSClient::RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); + if (rws_result.success && !rws_result.p_xml_document.isNull()) + { + std::ostringstream ostr; + Poco::XML::DOMWriter().writeNode(ostr, rws_result.p_xml_document); + return ostr.str() ; + } + return ""; + } +}; + +//thin wrappers for functions with default values +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getMechanicalUnitRobTarget_overloads, RWSInterface::getMechanicalUnitRobTarget, 2, 5) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(registerLocalUser_overloads, RWSInterface::registerLocalUser, 0, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(registerRemoteUser_overloads, RWSInterface::registerRemoteUser, 0, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getLogText_overloads, RWSInterface::getLogText, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getLogTextLatestEvent_overloads, RWSInterface::getLogTextLatestEvent, 0, 1) + +BOOST_PYTHON_MODULE(abb_librws) +{ + + using namespace boost::python; + + class_ >("string_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("RAPIDTaskInfo_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("Arm_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("Joint_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("MechanicalUnit_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("MechanicalUnitGroup_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("PresentOption_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("Robot_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("Single_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("Transmission_vector") + .def(vector_indexing_suite >()) + ; + + class_ >("RAPIDModuleInfo_vector") + .def(vector_indexing_suite >()) + ; + + + enum_("Motion") + .value("UNKNOWN_VALUE", TriBool::UNKNOWN_VALUE) + .value("TRUE_VALUE", TriBool::TRUE_VALUE) + .value("FALSE_VALUE", TriBool::FALSE_VALUE) + ; + + class_("TriBool") + .def(init()) + .def(init()) + .def("isUnknown", &TriBool::isUnknown) + .def("isTrue", &TriBool::isTrue) + .def("isFalse", &TriBool::isFalse) + .def("toString", &TriBool::toString) + .def("__str__", &TriBool::toString) + //TODO: Operator overrides + ; + + /*rws_config*/ + class_("Arm", no_init) + .def_readwrite("name", &cfg::moc::Arm::name) + .def_readwrite("lower_joint_bound", &cfg::moc::Arm::lower_joint_bound) + .def_readwrite("upper_joint_bound", &cfg::moc::Arm::upper_joint_bound) + ; + + class_("Joint", no_init) + .def_readwrite("name", &cfg::moc::Joint::name) + .def_readwrite("logical_axis", &cfg::moc::Joint::logical_axis) + .def_readwrite("kinematic_axis_number", &cfg::moc::Joint::kinematic_axis_number) + .def_readwrite("use_arm", &cfg::moc::Joint::use_arm) + .def_readwrite("use_transmission", &cfg::moc::Joint::use_transmission) + ; + + class_("MechanicalUnit", no_init) + .def_readwrite("name", &cfg::moc::MechanicalUnit::name) + .def_readwrite("use_robot", &cfg::moc::MechanicalUnit::use_robot) + .def_readwrite("use_singles", &cfg::moc::MechanicalUnit::use_singles) + ; + + class_("Robot", no_init) + .def_readwrite("name", &cfg::moc::Robot::name) + .def_readwrite("use_robot_type", &cfg::moc::Robot::use_robot_type) + .def_readwrite("use_joints", &cfg::moc::Robot::use_joints) + .def_readwrite("base_frame", &cfg::moc::Robot::base_frame) + .def_readwrite("base_frame_moved_by", &cfg::moc::Robot::base_frame_moved_by) + ; + + class_("Single", no_init) + .def_readwrite("name", &cfg::moc::Single::name) + .def_readwrite("use_single_type", &cfg::moc::Single::use_single_type) + .def_readwrite("use_joint", &cfg::moc::Single::use_joint) + .def_readwrite("base_frame", &cfg::moc::Single::base_frame) + .def_readwrite("base_frame_coordinated", &cfg::moc::Single::base_frame_coordinated) + ; + + class_("Transmission", no_init) + .def_readwrite("name", &cfg::moc::Transmission::name) + .def_readwrite("rotating_move", &cfg::moc::Transmission::rotating_move) + ; + + class_("MechanicalUnitGroup", no_init) + .def_readwrite("name", &cfg::sys::MechanicalUnitGroup::name) + .def_readwrite("robot", &cfg::sys::MechanicalUnitGroup::robot) + .def_readwrite("mechanical_units", &cfg::sys::MechanicalUnitGroup::mechanical_units) + ; + + class_("MechanicalUnitGroup", no_init) + .def_readwrite("name", &cfg::sys::PresentOption::name) + .def_readwrite("description", &cfg::sys::PresentOption::description) + ; + + /*rws_client*/ + class_("RAPIDSymbolResource", init()) + .def_readwrite("module", &RWSClient::RAPIDSymbolResource::module) + .def_readwrite("name", &RWSClient::RAPIDSymbolResource::name) + ; + + + class_("RAPIDResource", init()) + .def(init()) + .def_readwrite("task", &RWSClient::RAPIDResource::task) + .def_readwrite("module", &RWSClient::RAPIDResource::module) + .def_readwrite("name", &RWSClient::RAPIDResource::name) + ; + + class_("FileResource", init()) + .def(init()) + .def_readwrite("filename", &RWSClient::FileResource::filename) + .def_readwrite("directory", &RWSClient::FileResource::directory) + ; + + enum_("Priority") + .value("LOW", RWSClient::SubscriptionResources::LOW) + .value("MEDIUM", RWSClient::SubscriptionResources::MEDIUM) + .value("HIGH", RWSClient::SubscriptionResources::HIGH) + ; + + class_("SubscriptionResource", init()) + .def_readwrite("resource_uri", &RWSClient::SubscriptionResources::SubscriptionResource::resource_uri) + .def_readwrite("priority", &RWSClient::SubscriptionResources::SubscriptionResource::priority) + ; + + class_("SubscriptionResources") + .def("add", &RWSClient::SubscriptionResources::add) + .def("addIOSignal", &RWSClient::SubscriptionResources::addIOSignal) + .def("addRAPIDPersistantVariable", &RWSClient::SubscriptionResources::addRAPIDPersistantVariable) + //.def("getResources", &RWSClient::SubscriptionResources::getResources) + ; + + enum_("Coordinate") + .value("BASE", RWSClient::BASE) + .value("WORLD", RWSClient::WORLD) + .value("TOOL", RWSClient::TOOL) + .value("WOBJ", RWSClient::WOBJ) + .value("ACTIVE", RWSClient::ACTIVE) + ; + + + /*rws_rapid*/ + + class_("RAPIDSymbolDataAbstract", no_init) + .def("getType", &RAPIDSymbolDataAbstract::getType) + .def("parseString", &RAPIDSymbolDataAbstract::parseString) + .def("constructString", &RAPIDSymbolDataAbstract::constructString) + .def("__str__", &RAPIDSymbolDataAbstract::constructString) + ; + + class_ >("RAPIDBool", init<>()) + .def(init()) + ; + + implicitly_convertible(); + + class_ >("RAPIDNum", init<>()) + .def(init()) + ; + + implicitly_convertible(); + + class_ >("RAPIDDnum", init<>()) + .def(init()) + ; + + implicitly_convertible(); + + class_ >("RAPIDString", init<>()) + .def(init()) + ; + + implicitly_convertible(); + + + class_ >("RAPIDRecord", init()) + + ; + + class_ >("PyRAPIDRecord", init()) + .def("addComponents", &PyRAPIDRecord::addComponents) + + ; + + class_ >("RobJoint", init<>()) + .def_readwrite("rax_1", &RobJoint::rax_1) + .def_readwrite("rax_2", &RobJoint::rax_2) + .def_readwrite("rax_3", &RobJoint::rax_3) + .def_readwrite("rax_4", &RobJoint::rax_4) + .def_readwrite("rax_5", &RobJoint::rax_5) + .def_readwrite("rax_6", &RobJoint::rax_6) + ; + + class_ >("ExtJoint", init<>()) + .def_readwrite("eax_a", &ExtJoint::eax_a) + .def_readwrite("eax_b", &ExtJoint::eax_b) + .def_readwrite("eax_c", &ExtJoint::eax_c) + .def_readwrite("eax_d", &ExtJoint::eax_d) + .def_readwrite("eax_e", &ExtJoint::eax_e) + .def_readwrite("eax_f", &ExtJoint::eax_f) + ; + + class_ >("JointTarget", init<>()) + .def(init()) + .def_readwrite("robax", &JointTarget::robax) + .def_readwrite("extax", &JointTarget::extax) + ; + + class_ >("Pos", init<>()) + .def_readwrite("x", &Pos::x) + .def_readwrite("y", &Pos::y) + .def_readwrite("z", &Pos::z) + ; + + class_ >("Orient", init<>()) + .def_readwrite("q1", &Orient::q1) + .def_readwrite("q2", &Orient::q2) + .def_readwrite("q3", &Orient::q3) + .def_readwrite("q4", &Orient::q4) + ; + + class_ >("Pose", init<>()) + .def(init()) + .def_readwrite("pos", &Pose::pos) + .def_readwrite("rot", &Pose::rot) + ; + + class_ >("ConfData", init<>()) + .def_readwrite("q1", &ConfData::cf1) + .def_readwrite("q2", &ConfData::cf4) + .def_readwrite("q3", &ConfData::cf6) + .def_readwrite("q4", &ConfData::cfx) + ; + + class_ >("RobTarget", init<>()) + .def(init()) + .def_readwrite("pos", &RobTarget::pos) + .def_readwrite("orient", &RobTarget::orient) + .def_readwrite("robconf", &RobTarget::robconf) + .def_readwrite("extax", &RobTarget::extax) + ; + + class_ >("LoadData", init<>()) + .def(init()) + .def_readwrite("mass", &LoadData::mass) + .def_readwrite("cog", &LoadData::cog) + .def_readwrite("aom", &LoadData::aom) + .def_readwrite("ix", &LoadData::ix) + .def_readwrite("iy", &LoadData::iy) + .def_readwrite("iz", &LoadData::iz) + ; + + class_ >("ToolData", init<>()) + .def(init()) + .def_readwrite("robhold", &ToolData::robhold) + .def_readwrite("tframe", &ToolData::tframe) + .def_readwrite("tload", &ToolData::tload) + ; + + class_ >("WObjData", init<>()) + .def(init()) + .def_readwrite("robhold", &WObjData::robhold) + .def_readwrite("ufprog", &WObjData::ufprog) + .def_readwrite("ufmec", &WObjData::ufmec) + .def_readwrite("uframe", &WObjData::uframe) + .def_readwrite("oframe", &WObjData::oframe) + ; + + class_ >("SpeedData", init<>()) + .def_readwrite("v_tcp", &SpeedData::v_tcp) + .def_readwrite("v_ori", &SpeedData::v_ori) + .def_readwrite("v_leax", &SpeedData::v_leax) + .def_readwrite("v_reax", &SpeedData::v_reax) + ; + + /* RWSInterface */ + enum_("RAPIDTaskExecutionState") + .value("UNKNOWN", RWSInterface::UNKNOWN) + .value("READY", RWSInterface::READY) + .value("STOPPED", RWSInterface::STOPPED) + .value("STARTED", RWSInterface::STARTED) + .value("UNINITIALIZED", RWSInterface::UNINITIALIZED) + ; + + enum_("MechanicalUnitType") + .value("NONE", RWSInterface::NONE) + .value("TCP_ROBOT", RWSInterface::TCP_ROBOT) + .value("ROBOT", RWSInterface::ROBOT) + .value("SINGLE", RWSInterface::SINGLE) + .value("UNDEFINED", RWSInterface::UNDEFINED) + ; + + enum_("MechanicalUnitMode") + .value("UNKNOWN_MODE", RWSInterface::UNKNOWN_MODE) + .value("ACTIVATED", RWSInterface::ACTIVATED) + .value("DEACTIVATED", RWSInterface::DEACTIVATED) + ; + + class_("MechanicalUnitStaticInfo") + .def_readwrite("type", &RWSInterface::MechanicalUnitStaticInfo::type) + .def_readwrite("task_name", &RWSInterface::MechanicalUnitStaticInfo::task_name) + .def_readwrite("axes", &RWSInterface::MechanicalUnitStaticInfo::axes) + .def_readwrite("axes_total", &RWSInterface::MechanicalUnitStaticInfo::axes_total) + .def_readwrite("is_integrated_unit", &RWSInterface::MechanicalUnitStaticInfo::is_integrated_unit) + .def_readwrite("has_integrated_unit", &RWSInterface::MechanicalUnitStaticInfo::has_integrated_unit) + ; + + class_("MechanicalUnitDynamicInfo") + .def_readwrite("tool_name", &RWSInterface::MechanicalUnitDynamicInfo::tool_name) + .def_readwrite("wobj_name", &RWSInterface::MechanicalUnitDynamicInfo::wobj_name) + .def_readwrite("payload_name", &RWSInterface::MechanicalUnitDynamicInfo::payload_name) + .def_readwrite("total_payload_name", &RWSInterface::MechanicalUnitDynamicInfo::total_payload_name) + .def_readwrite("status", &RWSInterface::MechanicalUnitDynamicInfo::status) + .def_readwrite("mode", &RWSInterface::MechanicalUnitDynamicInfo::mode) + .def_readwrite("jog_mode", &RWSInterface::MechanicalUnitDynamicInfo::jog_mode) + .def_readwrite("coord_system", &RWSInterface::MechanicalUnitDynamicInfo::coord_system) + ; + + class_("SystemInfo") + .def_readwrite("robot_ware_version", &RWSInterface::SystemInfo::robot_ware_version) + .def_readwrite("system_name", &RWSInterface::SystemInfo::system_name) + .def_readwrite("system_type", &RWSInterface::SystemInfo::system_type) + .def_readwrite("system_options", &RWSInterface::SystemInfo::system_options) + ; + + class_("RobotWareOptionInfo", init()) + .def_readwrite("name", &RWSInterface::RobotWareOptionInfo::name) + .def_readwrite("description", &RWSInterface::RobotWareOptionInfo::description) + ; + + class_("RAPIDModuleInfo", init()) + .def_readwrite("name", &RWSInterface::RAPIDModuleInfo::name) + .def_readwrite("type", &RWSInterface::RAPIDModuleInfo::type) + ; + + class_("RAPIDTaskInfo", init()) + .def_readwrite("name", &RWSInterface::RAPIDTaskInfo::name) + .def_readwrite("is_motion_task", &RWSInterface::RAPIDTaskInfo::is_motion_task) + .def_readwrite("is_active", &RWSInterface::RAPIDTaskInfo::is_active) + .def_readwrite("execution_state", &RWSInterface::RAPIDTaskInfo::execution_state) + ; + + class_("StaticInfo") + .def_readwrite("rapid_tasks", &RWSInterface::StaticInfo::rapid_tasks) + .def_readwrite("system_info", &RWSInterface::StaticInfo::system_info) + ; + + class_("RuntimeInfo") + .def_readwrite("auto_mode", &RWSInterface::RuntimeInfo::auto_mode) + .def_readwrite("motors_on", &RWSInterface::RuntimeInfo::motors_on) + .def_readwrite("rapid_running", &RWSInterface::RuntimeInfo::rapid_running) + .def_readwrite("rws_connected", &RWSInterface::RuntimeInfo::rws_connected) + ; + + class_("RWSInterface", init()) + .def(init()) + .def(init()) + .def(init()) + + .def("collectRuntimeInfo", &RWSInterfacePy::collectRuntimeInfo) + .def("collectStaticInfo", &RWSInterfacePy::collectStaticInfo) + .def("getCFGArms", &RWSInterfacePy::getCFGArms) + .def("getCFGJoints", &RWSInterfacePy::getCFGJoints) + .def("getCFGMechanicalUnits", &RWSInterfacePy::getCFGMechanicalUnits) + .def("getCFGMechanicalUnitGroups", &RWSInterfacePy::getCFGMechanicalUnitGroups) + .def("getCFGPresentOptions", &RWSInterfacePy::getCFGPresentOptions) + .def("getCFGRobots", &RWSInterfacePy::getCFGRobots) + .def("getCFGSingles", &RWSInterfacePy::getCFGSingles) + .def("getCFGTransmission", &RWSInterfacePy::getCFGTransmission) + //Deprecated + //.def("getPresentRobotWareOptions", &RWSInterface::getPresentRobotWareOptions) + .def("getIOSignal", &RWSInterfacePy::getIOSignal) + .def("getMechanicalUnitStaticInfo", &RWSInterfacePy::getMechanicalUnitStaticInfo) + .def("getMechanicalUnitDynamicInfo", &RWSInterfacePy::getMechanicalUnitDynamicInfo) + .def("getMechanicalUnitJointTarget", &RWSInterfacePy::getMechanicalUnitJointTarget) + + .def("getMechanicalUnitRobTarget", + &RWSInterfacePy::getMechanicalUnitRobTarget, getMechanicalUnitRobTarget_overloads( + (arg("mechunit"), arg("p_robtarget"), arg("coordinate") = RWSClient::ACTIVE, + arg("tool") = "", arg("wobj") = ""))) + + + .def("getRAPIDSymbolData", &RWSInterfacePy::getRAPIDSymbolData) + .def("getRAPIDSymbolData", &RWSInterfacePy::getRAPIDSymbolData) + .def("getRAPIDSymbolData", &RWSInterfacePy::getRAPIDSymbolData) + + .def("getRAPIDModulesInfo", &RWSInterfacePy::getRAPIDModulesInfo) + .def("getRAPIDTasks", &RWSInterfacePy::getRAPIDTasks) + .def("getSpeedRatio", &RWSInterfacePy::getSpeedRatio) + .def("getSystemInfo", &RWSInterfacePy::getSystemInfo) + .def("isAutoMode", &RWSInterfacePy::isAutoMode) + .def("isMotorsOn", &RWSInterfacePy::isMotorsOn) + .def("isRAPIDRunning", &RWSInterfacePy::isRAPIDRunning) + .def("setIOSignal", &RWSInterfacePy::setIOSignal) + + .def("setRAPIDSymbolData", &RWSInterfacePy::setRAPIDSymbolData) + .def("setRAPIDSymbolData", &RWSInterfacePy::setRAPIDSymbolData) + .def("setRAPIDSymbolData", &RWSInterfacePy::setRAPIDSymbolData) + + .def("startRAPIDExecution", &RWSInterfacePy::startRAPIDExecution) + .def("stopRAPIDExecution", &RWSInterfacePy::stopRAPIDExecution) + .def("resetRAPIDProgramPointer", &RWSInterfacePy::resetRAPIDProgramPointer) + .def("setMotorsOn", &RWSInterfacePy::setMotorsOn) + .def("setMotorsOff", &RWSInterfacePy::setMotorsOff) + .def("setSpeedRatio", &RWSInterfacePy::setSpeedRatio) + .def("getFile", &RWSInterfacePy::getFile) + .def("uploadFile", &RWSInterfacePy::uploadFile) + .def("deleteFile", &RWSInterfacePy::deleteFile) + .def("startSubscription", &RWSInterfacePy::startSubscription) + .def("waitForSubscriptionEvent", &RWSInterfacePy::waitForSubscriptionEvent) + //.def*)>("waitForSubscriptionEvent", &RWSInterface::waitForSubscriptionEvent) + .def("waitForSubscriptionEventAsString", &RWSInterfacePy::waitForSubscriptionEventAsString) + .def("endSubscription", &RWSInterfacePy::endSubscription) + .def("forceCloseSubscription", &RWSInterfacePy::forceCloseSubscription) + .def("registerLocalUser", &RWSInterfacePy::registerLocalUser, + registerLocalUser_overloads((arg("username") = SystemConstants::General::DEFAULT_USERNAME, + arg("application") = SystemConstants::General::EXTERNAL_APPLICATION, + arg("location") = SystemConstants::General::EXTERNAL_LOCATION))) + .def("registerRemoteUser", &RWSInterfacePy::registerRemoteUser, + registerRemoteUser_overloads((arg("username") = SystemConstants::General::DEFAULT_USERNAME, + arg("application") = SystemConstants::General::EXTERNAL_APPLICATION, + arg("location") = SystemConstants::General::EXTERNAL_LOCATION))) + .def("getLogText", &RWSInterfacePy::getLogText, getLogText_overloads((arg("verbose") = false))) + .def("getLogTextLatestEvent", &RWSInterfacePy::getLogTextLatestEvent, getLogTextLatestEvent_overloads((arg("verbose") = false))) + .def("setHTTPTimeout", &RWSInterfacePy::setHTTPTimeout) + ; +} diff --git a/test/test_python.py b/test/test_python.py new file mode 100755 index 00000000..3bcd6bc0 --- /dev/null +++ b/test/test_python.py @@ -0,0 +1,194 @@ +#!/usr/bin/env python + +import abb_librws as abb +import sys +import time + + +class TRecord(abb.PyRAPIDRecord): + def __init__(self): + abb.PyRAPIDRecord.__init__(self, "TRecord") + self.Value = abb.RAPIDNum() + self.StringValue = abb.RAPIDString() + self.addComponents(self.Value) + self.addComponents(self.StringValue) + + +rws = abb.RWSInterface(sys.argv[1]) +start = time.time() +ri = rws.collectRuntimeInfo() +print("Runtime info") +print("------------") +print("Auto mode: {}\nMotors on {}\nRapid running {}\nRws connected {}".format(ri.auto_mode, ri.motors_on, ri.rapid_running, ri.rws_connected)) + +si = rws.collectStaticInfo() +print("") +print("System Info") +print("-----------") +print("System name: {}".format(si.system_info.system_name)) +print("System type: {}".format(si.system_info.system_type)) +print("Robotware version: {}".format(si.system_info.robot_ware_version)) +print("System options: {}".format(list(si.system_info.system_options))) +for rapid_task in si.rapid_tasks: + print("Task: name {}".format(rapid_task.name)) +print("") + +arms = rws.getCFGArms() +for arm in arms: + print("name: {}\tlower bound: {}\tupper_bound {}".format(arm.name, arm.lower_joint_bound, arm.upper_joint_bound)) + + +mechanical_units = rws.getCFGMechanicalUnits() +mechanical_unit_groups = rws.getCFGMechanicalUnitGroups() +present_options = rws.getCFGPresentOptions() +robots = rws.getCFGRobots() +singles = rws.getCFGSingles() +transmissions = rws.getCFGTransmission() +# deprecated +# robotware_option_info = rws.getPresentRobotWareOptions() + +mechanical_unit_static_info = abb.MechanicalUnitStaticInfo() +success = rws.getMechanicalUnitStaticInfo("ROB_1", mechanical_unit_static_info) +if success: + print("") + print("Mechanical Unit Static Info") + print("----------------------------") + print("Type: {}".format(mechanical_unit_static_info.type)) + print("Task name: {}".format(mechanical_unit_static_info.task_name)) + print("Axes: {}".format(mechanical_unit_static_info.axes)) + print("Axes total: {}".format(mechanical_unit_static_info.axes_total)) + print("is Integrated Unit: {}".format(mechanical_unit_static_info.is_integrated_unit)) + print("has Integrated Unit: {}".format(mechanical_unit_static_info.has_integrated_unit)) + print("") + pass + +mechanical_unit_dynamic_info = abb.MechanicalUnitDynamicInfo() +success = rws.getMechanicalUnitDynamicInfo("ROB_1", mechanical_unit_dynamic_info) +if success: + print("") + print("Mechanical Unit Dynamic Info") + print("----------------------------") + print("Tool name: {}".format(mechanical_unit_dynamic_info.tool_name)) + print("Wobj name: {}".format(mechanical_unit_dynamic_info.wobj_name)) + print("Payload name: {}".format(mechanical_unit_dynamic_info.payload_name)) + print("Total payload name: {}".format(mechanical_unit_dynamic_info.total_payload_name)) + print("Status: {}".format(mechanical_unit_dynamic_info.status)) + print("Mode: {}".format(mechanical_unit_dynamic_info.mode)) + print("Jog mode: {}".format(mechanical_unit_dynamic_info.jog_mode)) + print("Coordinate System: {}".format(mechanical_unit_dynamic_info.coord_system)) + print("") + +jointtarget = abb.JointTarget() +success = rws.getMechanicalUnitJointTarget("ROB_1", jointtarget) +if success: + print("Jointtarget is {}".format(jointtarget)) + +robtarget = abb.RobTarget() +success = rws.getMechanicalUnitRobTarget("ROB_1", robtarget) +if success: + print("RobTarget is {}".format(robtarget)) + pass + +# Iterate through all tasks and go through modules and print their info +rapid_tasks = rws.getRAPIDTasks(); +for rapid_task in rapid_tasks: + module_infos = rws.getRAPIDModulesInfo(rapid_task.name) + for module_info in module_infos: + print("Module: {}, type: {}".format(module_info.name, module_info.type)) + +speed_ratio = rws.getSpeedRatio() +print("Speed ratio: {}".format(speed_ratio)) + +logText = rws.getLogText() +print("log Text: {}".format(logText)) + +logTextverbose = rws.getLogText(True) +print("log Text Verbose: {}".format(logTextverbose)) + +# -------------------------- +# tests for data types +# -------------------------- +#bool +testBool = abb.RAPIDBool() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testBool", testBool) +if success: + print("Value of testBool is: {}".format(testBool)) +#num +testNum = abb.RAPIDNum() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testNum", testNum) +if success: + print("Value of testNum is: {}".format(testNum)) +#string +testString = abb.RAPIDString() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testString", testString) +if success: + print("Value of testString is: {}".format(testString)) +#RobJoint +testRobJoint = abb.RobJoint() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testRobJoint", testRobJoint) +if success: + print("Value of testRobJoint is: {}".format(testRobJoint)) +#ExtJoint +testExtJoint = abb.ExtJoint() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testExtJoint", testExtJoint) +if success: + print("Value of testNum is: {}".format(testExtJoint)) +#JointTarget +testJointTarget = abb.JointTarget() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testJointTarget", testJointTarget) +if success: + print("Value of testJointTarget is: {}".format(testJointTarget)) +#Pos +testPos = abb.Pos() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testPos", testPos) +if success: + print("Value of testPos is: {}".format(testPos)) +#Orient +testOrient = abb.Orient() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testOrient", testOrient) +if success: + print("Value of testOrient is: {}".format(testOrient)) +#Pose +testPose = abb.Pose() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testPose", testPose) +if success: + print("Value of testPose is: {}".format(testPose)) +#ConfData +testConfData = abb.ConfData() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testConfData", testConfData) +if success: + print("Value of testConfData is: {}".format(testConfData)) +#RobTarget +testRobTarget = abb.RobTarget() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testRobTarget", testRobTarget) +if success: + print("Value of testRobTarget is: {}".format(testRobTarget)) +#ToolData +testToolData = abb.ToolData() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testToolData", testToolData) +if success: + print("Value of testToolData is: {}".format(testToolData)) +#WObjData +testWObjData = abb.WObjData() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testWObjData", testWObjData) +if success: + print("Value of testWObjData is: {}".format(testWObjData)) +#SpeedData +testSpeedData = abb.SpeedData() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testSpeedData", testSpeedData) +if success: + print("Value of testSpeedData is: {}".format(testSpeedData)) +#LoadData +testLoadData = abb.LoadData() +success = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testLoadData", testLoadData) +if success: + print("Value of testLoadData is: {}".format(testLoadData)) +#CustomRecord +testRecord = rws.getRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testRecord") +print("Value of testRecord is: {}".format(testRecord)) + +record = TRecord() +record.parseString(testRecord) +print("Value of record is: {}".format(record)) + +print("Total time is {}".format(time.time() - start)) diff --git a/test/test_robot.mod b/test/test_robot.mod new file mode 100644 index 00000000..45ff69f9 --- /dev/null +++ b/test/test_robot.mod @@ -0,0 +1,24 @@ +MODULE ABB_LIBRWS + RECORD tRecord + Num Value; + String stringValue; + ENDRECORD + + TASK PERS bool testBool := TRUE; + TASK PERS num testNum := 123; + TASK PERS string testString := "Hello World"; + TASK PERS robJoint testRobJoint := [1,2,3,4,5,6]; + TASK PERS ExtJoint testExtJoint := [1,2,3,4,5,6]; + TASK PERS JointTarget testJointTarget := [[1,2,3,4,5,6],[1,2,3,4,5,6]]; + TASK PERS Pos testPos :=[1,2,3]; + TASK PERS Orient testOrient := [1,0,0,0]; + TASK PERS Pose testPose :=[[1,2,3],[1,0,0,0]]; + TASK PERS ConfData testConfData := [1,2,3,4]; + TASK PERS RobTarget testRobTarget := [[1,2,3],[1,0,0,0],[0,0,0,0],[0,0,0,0,0,0]]; + TASK PERS ToolData testToolData := [TRUE, [[0, 0, 0], [1, 0, 0, 0]], [0.001, [0, 0, 0.001],[1, 0, 0, 0], 0, 0, 0]]; + TASK PERS WobjData testWobjData := [FALSE, TRUE, "", [[1, 2, 3],[1, 0, 0, 0]],[[0, 0, 0],[1, 0, 0, 0]]]; + TASK PERS SpeedData testSpeedData := [1,0,0,0]; + TASK PERS LoadData testLoadData := [0.001, [0, 0, 0.001],[1, 0, 0, 0], 0, 0, 0]; + + TASK PERS tRecord testREcord := [1, "Hello World"]; +ENDMODULE \ No newline at end of file From ca8cc7fd145528483fc387b907be1f9a758dadf0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Filip=20=C3=84rlemalm?= Date: Tue, 4 May 2021 11:38:55 +0200 Subject: [PATCH 3/4] aadded support for RMMP --- include/abb_librws/rws_client.h | 26 ++++++++++++++ include/abb_librws/rws_common.h | 16 +++++++++ include/abb_librws/rws_interface.h | 55 ++++++++++++++++++++++++++++++ src/rws_client.cpp | 27 +++++++++++++++ src/rws_common.cpp | 3 ++ src/rws_interface.cpp | 27 +++++++++++++++ src/rws_poco_client.cpp | 9 +++-- src/rws_rapid.cpp | 2 +- test/testRMMP.py | 25 ++++++++++++++ test/test_python.py | 8 +++++ 10 files changed, 194 insertions(+), 4 deletions(-) create mode 100755 test/testRMMP.py diff --git a/include/abb_librws/rws_client.h b/include/abb_librws/rws_client.h index a1b3743e..fd6f3bb2 100644 --- a/include/abb_librws/rws_client.h +++ b/include/abb_librws/rws_client.h @@ -694,6 +694,30 @@ class RWSClient : public POCOClient const std::string& application = SystemConstants::General::EXTERNAL_APPLICATION, const std::string& location = SystemConstants::General::EXTERNAL_LOCATION); + + /** + * \brief A method for registering a user as remote. + * + * \param username specifying the user name. + * \param application specifying the external application. + * \param location specifying the location. + * + * \return RWSResult containing the result. + */ + RWSClient::RWSResult requestRMMP(); + + + /** + * \brief A method for registering a user as remote. + * + * \param username specifying the user name. + * \param application specifying the external application. + * \param location specifying the location. + * + * \return RWSResult containing the result. + */ + RWSClient::RWSResult getRMMPState(); + /** * \brief Method for parsing a communication result into a XML document. * @@ -720,6 +744,8 @@ class RWSClient : public POCOClient */ std::string getLogTextLatestEvent(const bool verbose = false); + + private: /** * \brief A struct for representing conditions, for the evaluation of an attempted RWS communication. diff --git a/include/abb_librws/rws_common.h b/include/abb_librws/rws_common.h index 52b823e4..ed9425b7 100644 --- a/include/abb_librws/rws_common.h +++ b/include/abb_librws/rws_common.h @@ -506,6 +506,11 @@ struct SystemConstants * \brief Class & type. */ static const XMLAttribute CLASS_TYPE; + + /** + * \brief Class User RMMP. + */ + static const XMLAttribute CLASS_USER_RMMP; /** * \brief Class & value. @@ -677,6 +682,11 @@ struct SystemConstants * \brief Type. */ static const std::string TYPE; + + /** + * \brief User RMMP. + */ + static const std::string USER_RMMP; /** * \brief Value. @@ -855,6 +865,12 @@ struct SystemConstants * \brief User service. */ static const std::string USERS; + + /** + * \brief RMMP Request Manual Mode Privileges. + */ + static const std::string RMMP; + }; }; }; diff --git a/include/abb_librws/rws_interface.h b/include/abb_librws/rws_interface.h index 7b44f15e..0378b1bd 100644 --- a/include/abb_librws/rws_interface.h +++ b/include/abb_librws/rws_interface.h @@ -368,6 +368,44 @@ class RWSInterface bool rws_connected; }; + struct RMMPState + { + /** + * \brief A default constructor. + */ + RMMPState() {} + + /** + * \brief User id + */ + int userid; + + /** + * \brief Alias for the user. For users on a Windows PC it is the Windows user name. + */ + std::string alias; + + /** + * \brief User location. For users on a PC it is the PC's network name. + */ + std::string location; + + /** + * \brief Name of the application the user is using. E.g., "RobotStudio-Online", "PickMaster" + */ + std::string application; + + /** + * \brief {none|pending modify|modify|exec} + */ + std::string privilege; + + /** + * \brief {true | false} whether the rmmp request and the current request are mady by same user. + */ + bool rmmpheldbyme; + }; + /** * \brief A constructor. * @@ -888,6 +926,23 @@ class RWSInterface bool 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); + /** + * \brief A method for registering a user as remote. + * + * \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 requestRMMP(); + + /** + * \brief A method for fetching RMMP State. + * + * \return RMMPState indicating if the communication was successful or not. + */ + bool getRMMPState(RMMPState &rmmp_state); /** * \brief A method for retrieving the internal log as a text string. diff --git a/src/rws_client.cpp b/src/rws_client.cpp index 256caf70..e44fafe3 100644 --- a/src/rws_client.cpp +++ b/src/rws_client.cpp @@ -660,6 +660,33 @@ RWSClient::RWSResult RWSClient::registerRemoteUser(const std::string& username, return result; } +RWSClient::RWSResult RWSClient::requestRMMP() +{ + std::string uri = Services::RMMP; + std::string content = "privilege=modify"; + + + EvaluationConditions evaluation_conditions; + evaluation_conditions.parse_message_into_xml = false; + evaluation_conditions.accepted_outcomes.push_back(HTTPResponse::HTTP_ACCEPTED); + + RWSResult result = evaluatePOCOResult(httpPost(uri, content), evaluation_conditions); + + return result; +} + +RWSClient::RWSResult RWSClient::getRMMPState() +{ + std::string uri = Services::RMMP; + + 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); +} + + /************************************************************ * Auxiliary methods */ diff --git a/src/rws_common.cpp b/src/rws_common.cpp index 56a37c8f..b47ad734 100644 --- a/src/rws_common.cpp +++ b/src/rws_common.cpp @@ -288,6 +288,7 @@ const std::string Identifiers::SYS_OPTION_LI = "sys-option-li"; const std::string Identifiers::SYS_SYSTEM_LI = "sys-system-li"; const std::string Identifiers::TITLE = "title"; const std::string Identifiers::TYPE = "type"; +const std::string Identifiers::USER_RMMP = "user-rmmp"; const std::string Identifiers::VALUE = "value"; const std::string Identifiers::CLASS = "class"; const std::string Identifiers::OPTION = "option"; @@ -305,6 +306,7 @@ const std::string Services::FILESERVICE = "/fileservice"; const std::string Services::RW = "/rw"; const std::string Services::SUBSCRIPTION = "/subscription"; const std::string Services::USERS = "/users"; +const std::string Services::RMMP = "/users/rmmp"; const std::string Resources::INSTANCES = "/instances"; const std::string Resources::JOINTTARGET = "/jointtarget"; const std::string Resources::LOGOUT = "/logout"; @@ -342,6 +344,7 @@ const XMLAttribute XMLAttributes::CLASS_STATE(Identifiers::CLASS , I 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); +const XMLAttribute XMLAttributes::CLASS_USER_RMMP(Identifiers::CLASS , Identifiers::USER_RMMP); const XMLAttribute XMLAttributes::CLASS_VALUE(Identifiers::CLASS , Identifiers::VALUE); const XMLAttribute XMLAttributes::CLASS_OPTION(Identifiers::CLASS , Identifiers::OPTION); diff --git a/src/rws_interface.cpp b/src/rws_interface.cpp index b964aee9..e546ad69 100644 --- a/src/rws_interface.cpp +++ b/src/rws_interface.cpp @@ -41,6 +41,9 @@ #include "abb_librws/rws_interface.h" #include "abb_librws/rws_rapid.h" +#include +#include + namespace { static const char EXCEPTION_GET_CFG[]{"Failed to get configuration instances"}; @@ -1047,6 +1050,30 @@ bool RWSInterface::registerRemoteUser(const std::string& username, return rws_client_.registerRemoteUser(username, application, location).success; } +bool RWSInterface::requestRMMP() +{ + return rws_client_.requestRMMP().success; +} + +bool RWSInterface::getRMMPState(RMMPState &rmmp_state) +{ + RWSClient::RWSResult rws_result = rws_client_.getRMMPState(); + + if(rws_result.success) + { + std::stringstream ss(xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "userid"))); + ss >> rmmp_state.userid; + //rmmp_state.userid = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "userid")); + rmmp_state.alias = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "alias")); + rmmp_state.location = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "location")); + rmmp_state.application = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "application")); + rmmp_state.privilege = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "privilege")); + rmmp_state.rmmpheldbyme = xmlFindTextContent(rws_result.p_xml_document, XMLAttribute("class", "rmmpheldbyme")) == "true"; + } + return rws_result.success; +} + + std::string RWSInterface::getLogText(const bool verbose) { return rws_client_.getLogText(verbose); diff --git a/src/rws_poco_client.cpp b/src/rws_poco_client.cpp index 2314571f..71dc87a8 100644 --- a/src/rws_poco_client.cpp +++ b/src/rws_poco_client.cpp @@ -42,6 +42,9 @@ #include "abb_librws/rws_poco_client.h" +#include +#include + using namespace Poco; using namespace Poco::Net; @@ -249,8 +252,9 @@ POCOClient::POCOResult POCOClient::makeHTTPRequest(const std::string& method, request.setCookies(cookies_); request.setContentLength(content.length()); if (method == HTTPRequest::HTTP_POST || !content.empty()) - { - request.setContentType("application/x-www-form-urlencoded"); + { + request.set("Accept", "application/json"); + request.setContentType("application/x-www-form-urlencoded;v=2.0"); } // Attempt the communication. @@ -491,7 +495,6 @@ void POCOClient::sendAndReceive(POCOResult& result, { // Add request info to the result. result.addHTTPRequestInfo(request, request_content); - // Contact the server. std::string response_content; http_client_session_.sendRequest(request) << request_content; diff --git a/src/rws_rapid.cpp b/src/rws_rapid.cpp index 60b7ccf0..9a15d39e 100644 --- a/src/rws_rapid.cpp +++ b/src/rws_rapid.cpp @@ -34,6 +34,7 @@ *********************************************************************************************************************** */ +#include #include #include @@ -131,7 +132,6 @@ void RAPIDAtomic::parseString(const std::string& value_string) { temp.erase(position, 1); } - std::stringstream ss(temp); ss >> value; } diff --git a/test/testRMMP.py b/test/testRMMP.py new file mode 100755 index 00000000..c1eb3e37 --- /dev/null +++ b/test/testRMMP.py @@ -0,0 +1,25 @@ +#!/usr/bin/env python + +import abb_librws as abb +import sys +import time +import rospy + +rospy.init_node("swetree_cloud") +rws = abb.RWSInterface(sys.argv[1]) +rmmp_state = abb.RMMPState() + +if rws.isAutoMode().isFalse(): + print("The robot is not in Auto Mode, Requesting RMMP.") + rws.requestRMMP() + while rmmp_state.privilege != "modify": + rws.getRMMPState(rmmp_state) + rospy.sleep(1) + rospy.loginfo("Access granted") + for i in range(10): + rospy.loginfo(i) + rws.setRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testNum", "123432") + + +# rospy.loginfo("{} started".format(rospy.get_name())) +rospy.spin() diff --git a/test/test_python.py b/test/test_python.py index 3bcd6bc0..092bced0 100755 --- a/test/test_python.py +++ b/test/test_python.py @@ -15,6 +15,9 @@ def __init__(self): rws = abb.RWSInterface(sys.argv[1]) +r = rws.loginAsLocalUser() +r = rws.requestRMMP() +print(r) start = time.time() ri = rws.collectRuntimeInfo() print("Runtime info") @@ -192,3 +195,8 @@ def __init__(self): print("Value of record is: {}".format(record)) print("Total time is {}".format(time.time() - start)) + +print(record.Value.value + 1) + + +rws.setRAPIDSymbolData("T_ROB1", "ABB_LIBRWS", "testNum", "157") \ No newline at end of file From 65788cb8ddd990c84b6a0856e4fbd55347eb0c02 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Filip=20=C3=84rlemalm?= Date: Tue, 4 May 2021 11:39:17 +0200 Subject: [PATCH 4/4] RMMP Support, GIL Release --- python/rws_interface_py.cpp | 31 +++++++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) diff --git a/python/rws_interface_py.cpp b/python/rws_interface_py.cpp index 91d30c73..0ea389a2 100644 --- a/python/rws_interface_py.cpp +++ b/python/rws_interface_py.cpp @@ -52,6 +52,19 @@ using namespace abb::rws; +class releaseGIL{ +public: + inline releaseGIL(){ + save_state = PyEval_SaveThread(); + } + + inline ~releaseGIL(){ + PyEval_RestoreThread(save_state); + } +private: + PyThreadState *save_state; +}; + class PyRAPIDRecord : public RAPIDRecord { public: @@ -70,6 +83,7 @@ class RWSInterfacePy : public RWSInterface public: std::string waitForSubscriptionEventAsString() { + releaseGIL unlock = releaseGIL(); RWSClient::RWSResult rws_result = rws_client_.waitForSubscriptionEvent(); if (rws_result.success && !rws_result.p_xml_document.isNull()) { @@ -91,6 +105,7 @@ BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getLogTextLatestEvent_overloads, RWSInter BOOST_PYTHON_MODULE(abb_librws) { + PyEval_InitThreads(); using namespace boost::python; class_ >("string_vector") @@ -266,24 +281,28 @@ BOOST_PYTHON_MODULE(abb_librws) class_ >("RAPIDBool", init<>()) .def(init()) + .def_readwrite("value", &RAPIDBool::value) ; implicitly_convertible(); class_ >("RAPIDNum", init<>()) .def(init()) + .def_readwrite("value", &RAPIDNum::value) ; implicitly_convertible(); class_ >("RAPIDDnum", init<>()) .def(init()) + .def_readwrite("value", &RAPIDDnum::value) ; implicitly_convertible(); class_ >("RAPIDString", init<>()) .def(init()) + .def_readwrite("value", &RAPIDString::value) ; implicitly_convertible(); @@ -468,6 +487,15 @@ BOOST_PYTHON_MODULE(abb_librws) .def_readwrite("rws_connected", &RWSInterface::RuntimeInfo::rws_connected) ; + class_("RMMPState") + .def_readwrite("userid", &RWSInterface::RMMPState::userid) + .def_readwrite("alias", &RWSInterface::RMMPState::alias) + .def_readwrite("location", &RWSInterface::RMMPState::location) + .def_readwrite("application", &RWSInterface::RMMPState::application) + .def_readwrite("privilege", &RWSInterface::RMMPState::privilege) + .def_readwrite("rmmpheldbyme", &RWSInterface::RMMPState::rmmpheldbyme) + ; + class_("RWSInterface", init()) .def(init()) .def(init()) @@ -537,6 +565,9 @@ BOOST_PYTHON_MODULE(abb_librws) registerRemoteUser_overloads((arg("username") = SystemConstants::General::DEFAULT_USERNAME, arg("application") = SystemConstants::General::EXTERNAL_APPLICATION, arg("location") = SystemConstants::General::EXTERNAL_LOCATION))) + .def("requestRMMP", &RWSInterfacePy::requestRMMP) + .def("getRMMPState", &RWSInterfacePy::getRMMPState) + .def("getLogText", &RWSInterfacePy::getLogText, getLogText_overloads((arg("verbose") = false))) .def("getLogTextLatestEvent", &RWSInterfacePy::getLogTextLatestEvent, getLogTextLatestEvent_overloads((arg("verbose") = false))) .def("setHTTPTimeout", &RWSInterfacePy::setHTTPTimeout)