abb_ros2
abb_ros2 copied to clipboard
Support for ABB Omnicore + Robotware 7.0
Greetings,
Congratulations on the latest release! The packages here will greatly benefit a lot of people including myself.
I apologize if this is a misplaced question and should be targeted at abb_libegm
instead.
I'm curious about the effort needed to make this driver compatible with newer ABB
robots that ship with Omnicore
controllers running Robotware >= 7.0
. I understand from the description that only IRC
controllers with Robotware < 7.0
are presently supported.
It would be great if someone could highlight the exact set of items that need to be accomplished to achieve this goal. (what functionalities to add to which packages for example). I would be happy to contribute development effort on these items assuming I have the capability 😄
I have not tried yet but planning to soon. It seems from https://github.com/ros-industrial/abb_libegm/issues/118 that the underlying EGM protocol should function fine. The RWS interface may not work though. Have you tried it yet?
No, it will not work.
At least not with the default version of abb_librws
.
The fork maintained by NoMagic tries to address this: ros-industrial/abb_librws#147.
Thanks a lot for the suggestions. Will explore those options and report my findings here.
I looked into this and have encountered compilation errors in the rws_service_provider_ros.cpp file:
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:1098:31: error: ‘abb::rws::RWSStateMachineInterface’ has not been declared
1098 | rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) {
| ^~~
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp: In lambda function:
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:1102:19: error: request for member ‘setRAPIDSymbolData’ in ‘interface’, which is of non-class type ‘int’
1102 | if (interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_COMMAND_INPUT, sg_command_input) &&
| ^~~~~~~~~~~~~~~~~~
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:1102:49: error: ‘RAPIDSymbols’ has not been declared
1102 | if (interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_COMMAND_INPUT, sg_command_input) &&
| ^~~~~~~~~~~~
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:1103:19: error: request for member ‘setRAPIDSymbolData’ in ‘interface’, which is of non-class type ‘int’
1103 | interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_TARGET_POSTION_INPUT, sg_target_position_input))
| ^~~~~~~~~~~~~~~~~~
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:1103:49: error: ‘RAPIDSymbols’ has not been declared
1103 | interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_TARGET_POSTION_INPUT, sg_target_position_input))
| ^~~~~~~~~~~~
In file included from /opt/ros/humble/include/rclcpp/rclcpp/client.hpp:40,
from /opt/ros/humble/include/rclcpp/rclcpp/callback_group.hpp:24,
from /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp:20,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp:18,
from /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp:20,
from /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp:37,
from /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp:25,
from /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp:21,
from /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp:155,
from /home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp:46,
from /home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:41:
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:1111:58: error: request for member ‘getLogTextLatestEvent’ in ‘interface’, which is of non-class type ‘int’
1111 | RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent());
| ^~~~~~~~~~~~~~~~~~~~~
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp: In member function ‘bool abb_rws_client::RWSServiceProviderROS::setSGCommand(abb_rapid_sm_addin_msgs::srv::SetSGCommand_Request_<std::allocator<void> >::SharedPtr, abb_rapid_sm_addin_msgs::srv::SetSGCommand_Response_<std::allocator<void> >::SharedPtr)’:
/home/nuc-haptics/ws_abb_ros2/src/abb_ros2/abb_rws_client/src/rws_service_provider_ros.cpp:1098:26: error: cannot convert ‘abb_rws_client::RWSServiceProviderROS::setSGCommand(abb_rapid_sm_addin_msgs::srv::SetSGCommand_Request_<std::allocator<void> >::SharedPtr, abb_rapid_sm_addin_msgs::srv::SetSGCommand_Response_<std::allocator<void> >::SharedPtr)::<lambda(int&)>’ to ‘const ServiceFunctor&’ {aka ‘const std::function<void(abb::rws::v2_0::RWSStateMachineInterface&)>&’}
1098 | rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) {
| ~~~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1099 | abb::rws::RAPIDNum sg_command_input = static_cast<float>(req_command);
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1100 | abb::rws::RAPIDNum sg_target_position_input = req->target_position;
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1101 |
|
1102 | if (interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_COMMAND_INPUT, sg_command_input) &&
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1103 | interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_TARGET_POSTION_INPUT, sg_target_position_input))
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1104 | {
| ~
1105 | res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS;
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1106 | }
| ~
1107 | else
| ~~~~
1108 | {
| ~
1109 | res->message = abb_robot_msgs::msg::ServiceResponses::FAILED;
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1110 | res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED;
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1111 | RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent());
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1112 | }
| ~
1113 | });
Will look into it further
I gave up on trying to interface via RWS 2.0- it's a beast. But I've been successfully commanding an Omnicore robot using this driver by modifying the hardware interface such that I do not get the initial join information via RWS but instead hardcode it https://github.com/Yadunund/abb_ros2/blob/fa9338c800f4a48cc1ed4bea74c05b3928ec16cd/abb_hardware_interface/src/abb_hardware_interface.cpp#L44-L93. RWS is only really used at the start to get the configuration of this robot.
I plan to open a PR which will allow users to get this infromation from the ros2_control.xacro instead if they do not want to rely on RWS. This way no hardcoding should be needed.
I've opened this PR that does not require any hardcoding. Would be great if someone else can give it a spin and share their findings.