Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions ur_robot_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,7 @@ ament_target_dependencies(controller_stopper_node ${${PROJECT_NAME}_EXPORTED_TAR
add_executable(robot_state_helper
src/robot_state_helper.cpp
src/robot_state_helper_node.cpp
src/urcl_log_handler.cpp
)
target_link_libraries(robot_state_helper ur_client_library::urcl)
ament_target_dependencies(robot_state_helper ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
// UR client library
#include "ur_client_library/ur/dashboard_client.h"
#include "ur_client_library/exceptions.h"
#include "ur_dashboard_msgs/msg/program_state.hpp"
#include "ur_client_library/primary/primary_client.h"
#include "ur_dashboard_msgs/srv/add_to_log.hpp"
#include "ur_dashboard_msgs/srv/get_loaded_program.hpp"
#include "ur_dashboard_msgs/srv/get_program_state.hpp"
Expand Down Expand Up @@ -120,6 +120,9 @@ class DashboardClientROS
std::shared_ptr<rclcpp::Node> node_;
urcl::DashboardClient client_;

urcl::comm::INotifier notifier_;
urcl::primary_interface::PrimaryClient primary_client_;

// Commanding services
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr brake_release_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr clear_operational_mode_service_;
Expand Down
12 changes: 6 additions & 6 deletions ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#ifndef UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
#define UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_

#include <chrono>
#include <string>
#include <memory>

#include "rclcpp/rclcpp.hpp"
Expand All @@ -41,6 +41,7 @@
#include "ur_dashboard_msgs/msg/safety_mode.hpp"
#include "ur_dashboard_msgs/msg/robot_mode.hpp"
#include "ur_client_library/ur/datatypes.h"
#include "ur_client_library/primary/primary_client.h"

namespace ur_robot_driver
{
Expand Down Expand Up @@ -90,6 +91,10 @@ class RobotStateHelper
std::atomic<bool> program_running_;
std::mutex goal_mutex_;

std::string robot_ip_;
urcl::comm::INotifier notifier_;
std::shared_ptr<urcl::primary_interface::PrimaryClient> primary_client_;

rclcpp_action::Server<ur_dashboard_msgs::action::SetMode>::SharedPtr set_mode_as_;

rclcpp::CallbackGroup::SharedPtr robot_mode_sub_cb_;
Expand All @@ -100,12 +105,7 @@ class RobotStateHelper

rclcpp::CallbackGroup::SharedPtr service_cb_grp_;

rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr unlock_protective_stop_srv_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr restart_safety_srv_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_on_srv_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_off_srv_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr brake_release_srv_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr stop_program_srv_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr play_program_srv_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr resend_robot_program_srv_;
};
Expand Down
2 changes: 2 additions & 0 deletions ur_robot_driver/launch/ur_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -96,8 +96,10 @@ def launch_setup(context):
executable="robot_state_helper",
name="ur_robot_state_helper",
output="screen",
condition=UnlessCondition(use_mock_hardware),
parameters=[
{"headless_mode": headless_mode},
{"robot_ip": robot_ip},
],
)

Expand Down
14 changes: 12 additions & 2 deletions ur_robot_driver/src/dashboard_client_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,10 @@

#include "ur_robot_driver/dashboard_client_ros.hpp"

#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include <rclcpp/logging.hpp>
#include "ur_robot_driver/urcl_log_handler.hpp"

int main(int argc, char** argv)
Expand All @@ -53,7 +54,16 @@

ur_robot_driver::registerUrclLogHandler(""); // Set empty tf_prefix at the moment

ur_robot_driver::DashboardClientROS client(node, robot_ip);
std::shared_ptr<ur_robot_driver::DashboardClientROS> client;
try {
client = std::make_shared<ur_robot_driver::DashboardClientROS>(node, robot_ip);
} catch (const urcl::UrException& e) {
RCLCPP_WARN(rclcpp::get_logger("Dashboard_Client"),

Check warning on line 61 in ur_robot_driver/src/dashboard_client_node.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/dashboard_client_node.cpp#L57-L61

Added lines #L57 - L61 were not covered by tests
"%s This warning is expected on a PolyScopeX robot. If you don't want to see this warning, "
"please don't start the dashboard client. Exiting dashboard client now.",
e.what());
return 0;
}

Check warning on line 66 in ur_robot_driver/src/dashboard_client_node.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/dashboard_client_node.cpp#L65-L66

Added lines #L65 - L66 were not covered by tests

rclcpp::spin(node);

Expand Down
15 changes: 13 additions & 2 deletions ur_robot_driver/src/dashboard_client_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,16 +37,27 @@
*/
//----------------------------------------------------------------------

#include <ur_robot_driver/dashboard_client_ros.hpp>
#include <ur_client_library/exceptions.h>
#include <ur_client_library/primary/primary_client.h>

#include <string>

#include <ur_robot_driver/dashboard_client_ros.hpp>

namespace ur_robot_driver
{
DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip)
: node_(node), client_(robot_ip)
: node_(node), client_(robot_ip), primary_client_(robot_ip, notifier_)

Check warning on line 50 in ur_robot_driver/src/dashboard_client_ros.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/dashboard_client_ros.cpp#L50

Added line #L50 was not covered by tests
{
node_->declare_parameter<double>("receive_timeout", 1);

primary_client_.start(10, std::chrono::seconds(10));
auto robot_version = primary_client_.getRobotVersion();

Check warning on line 55 in ur_robot_driver/src/dashboard_client_ros.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/dashboard_client_ros.cpp#L54-L55

Added lines #L54 - L55 were not covered by tests

if (robot_version->major > 5) {
throw(urcl::UrException("The dashboard server is only available for CB3 and e-Series robots."));

Check warning on line 58 in ur_robot_driver/src/dashboard_client_ros.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/dashboard_client_ros.cpp#L58

Added line #L58 was not covered by tests
}

connect();

// Service to release the brakes. If the robot is currently powered off, it will get powered on on the fly.
Expand Down
108 changes: 65 additions & 43 deletions ur_robot_driver/src/robot_state_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
// POSSIBILITY OF SUCH DAMAGE.

#include <mutex>
#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>
#include <ur_robot_driver/robot_state_helper.hpp>

#include "rclcpp/rclcpp.hpp"
Expand Down Expand Up @@ -66,28 +68,27 @@
node->declare_parameter("headless_mode", false);
headless_mode_ = node->get_parameter("headless_mode").as_bool();

// Service to unlock protective stop
unlock_protective_stop_srv_ = node_->create_client<std_srvs::srv::Trigger>(
"dashboard_client/unlock_protective_stop", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
// Service to restart safety
restart_safety_srv_ = node_->create_client<std_srvs::srv::Trigger>(
"dashboard_client/restart_safety", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
// Service to power on the robot
power_on_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/power_on",
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
// Service to power off the robot
power_off_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/power_off",
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
// Service to release the robot's brakes
brake_release_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/brake_release",
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
// Service to stop UR program execution on the robot
stop_program_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/stop",
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
// Service to start UR program execution on the robot
play_program_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/play",
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
play_program_srv_->wait_for_service();
node->declare_parameter("robot_ip", "192.168.56.101");
robot_ip_ = node->get_parameter("robot_ip").as_string();

Check warning on line 72 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L71-L72

Added lines #L71 - L72 were not covered by tests

primary_client_ = std::make_shared<urcl::primary_interface::PrimaryClient>(robot_ip_, notifier_);

Check warning on line 74 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L74

Added line #L74 was not covered by tests

primary_client_->start(0, std::chrono::seconds(10));
auto robot_version = primary_client_->getRobotVersion();

Check warning on line 77 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L76-L77

Added lines #L76 - L77 were not covered by tests

if (robot_version->major > 5) {
RCLCPP_WARN(rclcpp::get_logger("robot_state_helper"), "Running on a PolyScopeX robot. The dashboard server is not "

Check warning on line 80 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L80

Added line #L80 was not covered by tests
"available, therefore the robot_state_helper cannot start "
"PolyScope programs and restart the safety.");
} else {
// Service to restart safety
restart_safety_srv_ = node_->create_client<std_srvs::srv::Trigger>(
"dashboard_client/restart_safety", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);

Check warning on line 86 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L85-L86

Added lines #L85 - L86 were not covered by tests
// Service to start UR program execution on the robot
play_program_srv_ = node_->create_client<std_srvs::srv::Trigger>(
"dashboard_client/play", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
play_program_srv_->wait_for_service();

Check warning on line 90 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L88-L90

Added lines #L88 - L90 were not covered by tests
}

resend_robot_program_srv_ = node_->create_client<std_srvs::srv::Trigger>(
"io_and_status_controller/resend_robot_program", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
Expand Down Expand Up @@ -136,7 +137,13 @@
{
switch (safety_mode_) {
case urcl::SafetyMode::PROTECTIVE_STOP:
return safeDashboardTrigger(this->unlock_protective_stop_srv_);
try {
primary_client_->commandUnlockProtectiveStop();
} catch (const urcl::UrException& e) {
RCLCPP_WARN_STREAM(rclcpp::get_logger("robot_state_helper"), e.what());
return false;
}
return true;

Check warning on line 146 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L140-L146

Added lines #L140 - L146 were not covered by tests
case urcl::SafetyMode::SYSTEM_EMERGENCY_STOP:;
case urcl::SafetyMode::ROBOT_EMERGENCY_STOP:
RCLCPP_WARN_STREAM(rclcpp::get_logger("robot_state_helper"), "The robot is currently in safety mode."
Expand All @@ -145,7 +152,11 @@
return false;
case urcl::SafetyMode::VIOLATION:;
case urcl::SafetyMode::FAULT:
return safeDashboardTrigger(this->restart_safety_srv_);
if (restart_safety_srv_ != nullptr) {
return safeDashboardTrigger(this->restart_safety_srv_);

Check warning on line 156 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L156

Added line #L156 was not covered by tests
} else {
return false;
}
default:
// nothing to do
RCLCPP_DEBUG_STREAM(rclcpp::get_logger("robot_state_helper"), "No safety recovery needed.");
Expand All @@ -155,15 +166,22 @@

bool RobotStateHelper::jumpToRobotMode(const urcl::RobotMode target_mode)
{
switch (target_mode) {
case urcl::RobotMode::POWER_OFF:
return safeDashboardTrigger(this->power_off_srv_);
case urcl::RobotMode::IDLE:
return safeDashboardTrigger(this->power_on_srv_);
case urcl::RobotMode::RUNNING:
return safeDashboardTrigger(this->brake_release_srv_);
default:
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), "Unreachable target robot mode.");
try {
switch (target_mode) {
case urcl::RobotMode::POWER_OFF:
primary_client_->commandPowerOff();
return true;
case urcl::RobotMode::IDLE:
primary_client_->commandPowerOn();
return true;
case urcl::RobotMode::RUNNING:
primary_client_->commandBrakeRelease();
return true;
default:
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), "Unreachable target robot mode.");

Check warning on line 181 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L169-L181

Added lines #L169 - L181 were not covered by tests
}
} catch (const urcl::UrException& e) {
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), e.what());

Check warning on line 184 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L183-L184

Added lines #L183 - L184 were not covered by tests
}
return false;
}
Expand Down Expand Up @@ -247,14 +265,13 @@

bool RobotStateHelper::stopProgram()
{
if (safeDashboardTrigger(this->stop_program_srv_)) {
auto start = std::chrono::steady_clock::now();
while (program_running_ && std::chrono::steady_clock::now() - start < std::chrono::seconds(1)) {
std::this_thread::sleep_for(std::chrono::milliseconds(2));
return true;
}
try {
primary_client_->commandStop();
} catch (const urcl::UrException& e) {
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), e.what());
return false;

Check warning on line 272 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L268-L272

Added lines #L268 - L272 were not covered by tests
}
return false;
return true;

Check warning on line 274 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L274

Added line #L274 was not covered by tests
}

void RobotStateHelper::setModeExecute(const std::shared_ptr<RobotStateHelper::SetModeGoalHandle> goal_handle)
Expand Down Expand Up @@ -344,9 +361,14 @@
if (headless_mode_) {
result_->success = safeDashboardTrigger(this->resend_robot_program_srv_);
} else {
// The dashboard denies playing immediately after switching the mode to RUNNING
sleep(1);
result_->success = safeDashboardTrigger(this->play_program_srv_);
if (play_program_srv_ == nullptr) {
result_->success = false;
result_->message = "Play program service not available on this robot.";

Check warning on line 366 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L365-L366

Added lines #L365 - L366 were not covered by tests
} else {
// The dashboard denies playing immediately after switching the mode to RUNNING
sleep(1);
result_->success = safeDashboardTrigger(this->play_program_srv_);

Check warning on line 370 in ur_robot_driver/src/robot_state_helper.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper.cpp#L369-L370

Added lines #L369 - L370 were not covered by tests
}
}
}
if (result_->success) {
Expand Down
9 changes: 8 additions & 1 deletion ur_robot_driver/src/robot_state_helper_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,19 @@
// POSSIBILITY OF SUCH DAMAGE.

#include "ur_robot_driver/robot_state_helper.hpp"
#include "ur_robot_driver/urcl_log_handler.hpp"

int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("robot_state_helper");
ur_robot_driver::RobotStateHelper state_helper(node);
ur_robot_driver::registerUrclLogHandler(""); // Set empty tf_prefix at the moment
std::shared_ptr<ur_robot_driver::RobotStateHelper> robot_state_helper;
try {
robot_state_helper = std::make_shared<ur_robot_driver::RobotStateHelper>(node);
} catch (const urcl::UrException& e) {
RCLCPP_ERROR(rclcpp::get_logger("robot_state_helper"), "%s", e.what());
}

Check warning on line 42 in ur_robot_driver/src/robot_state_helper_node.cpp

View check run for this annotation

Codecov / codecov/patch

ur_robot_driver/src/robot_state_helper_node.cpp#L36-L42

Added lines #L36 - L42 were not covered by tests

rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
Expand Down
Loading