Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
96 changes: 62 additions & 34 deletions ur_controllers/src/force_mode_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,9 @@ controller_interface::CallbackReturn
ur_controllers::ForceModeController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
{
// Stop force mode if this controller is deactivated.
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
if (!command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0)) {
return LifecycleNodeInterface::CallbackReturn::ERROR;
}
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}

Expand All @@ -175,54 +177,80 @@ controller_interface::return_type ur_controllers::ForceModeController::update(co

// Publish state of force_mode?
if (change_requested_) {
bool write_successful = true;
if (force_mode_active_) {
const auto force_mode_parameters = force_mode_params_buffer_.readFromRT();
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value(force_mode_parameters->task_frame[0]);
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value(force_mode_parameters->task_frame[1]);
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value(force_mode_parameters->task_frame[2]);
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value(force_mode_parameters->task_frame[3]);
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value(force_mode_parameters->task_frame[4]);
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value(force_mode_parameters->task_frame[5]);

command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value(
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value(
force_mode_parameters->task_frame[0]);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value(
force_mode_parameters->task_frame[1]);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value(
force_mode_parameters->task_frame[2]);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value(
force_mode_parameters->task_frame[3]);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value(
force_mode_parameters->task_frame[4]);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value(
force_mode_parameters->task_frame[5]);

write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value(
force_mode_parameters->selection_vec[0]);
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value(
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value(
force_mode_parameters->selection_vec[1]);
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value(
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value(
force_mode_parameters->selection_vec[2]);
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value(
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value(
force_mode_parameters->selection_vec[3]);
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value(
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value(
force_mode_parameters->selection_vec[4]);
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value(
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value(
force_mode_parameters->selection_vec[5]);

command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(force_mode_parameters->wrench.force.x);
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(force_mode_parameters->wrench.force.y);
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(force_mode_parameters->wrench.force.z);
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(force_mode_parameters->wrench.torque.x);
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(force_mode_parameters->wrench.torque.y);
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(force_mode_parameters->wrench.torque.z);

command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value(force_mode_parameters->limits[0]);
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value(force_mode_parameters->limits[1]);
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value(force_mode_parameters->limits[2]);
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value(force_mode_parameters->limits[3]);
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value(force_mode_parameters->limits[4]);
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value(force_mode_parameters->limits[5]);

command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value(force_mode_parameters->type);
command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value(force_mode_parameters->damping_factor);
command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value(force_mode_parameters->gain_scaling);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(force_mode_parameters->wrench.force.x);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(force_mode_parameters->wrench.force.y);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(force_mode_parameters->wrench.force.z);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(
force_mode_parameters->wrench.torque.x);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(
force_mode_parameters->wrench.torque.y);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(
force_mode_parameters->wrench.torque.z);

write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value(force_mode_parameters->limits[0]);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value(force_mode_parameters->limits[1]);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value(force_mode_parameters->limits[2]);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value(force_mode_parameters->limits[3]);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value(force_mode_parameters->limits[4]);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value(force_mode_parameters->limits[5]);

write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value(force_mode_parameters->type);
write_successful &=
command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value(force_mode_parameters->damping_factor);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value(
force_mode_parameters->gain_scaling);

// Signal that we are waiting for confirmation that force mode is activated
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
async_state_ = ASYNC_WAITING;
} else {
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
async_state_ = ASYNC_WAITING;
}
if (!write_successful) {
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to a command interfaces.");
return controller_interface::return_type::ERROR;
}
change_requested_ = false;
}

Expand Down
24 changes: 18 additions & 6 deletions ur_controllers/src/freedrive_mode_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,10 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
[&](auto& interface) { return (interface.get_name() == interface_name); });
if (it != command_interfaces_.end()) {
abort_command_interface_ = *it;
abort_command_interface_->get().set_value(0.0);
if (!abort_command_interface_->get().set_value(0.0)) {
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to abort command interface.");
return controller_interface::CallbackReturn::ERROR;
}
} else {
RCLCPP_ERROR(get_node()->get_logger(), "Did not find '%s' in command interfaces.", interface_name.c_str());
return controller_interface::CallbackReturn::ERROR;
Expand All @@ -166,7 +169,10 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
controller_interface::CallbackReturn
ur_controllers::FreedriveModeController::on_cleanup(const rclcpp_lifecycle::State& /*previous_state*/)
{
abort_command_interface_->get().set_value(1.0);
if (!abort_command_interface_->get().set_value(1.0)) {
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to abort command interface.");
return controller_interface::CallbackReturn::ERROR;
}

stop_logging_thread();

Expand All @@ -190,6 +196,7 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
async_state_ = async_success_command_interface_->get().get_value();

if (change_requested_) {
bool write_success = true;
if (freedrive_active_) {
// Check if the freedrive mode has been aborted from the hardware interface. E.g. the robot was stopped on the
// teach pendant.
Expand All @@ -202,22 +209,27 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
RCLCPP_INFO(get_node()->get_logger(), "Received command to start Freedrive Mode.");

// Set command interface to enable
enable_command_interface_->get().set_value(1.0);
write_success &= enable_command_interface_->get().set_value(1.0);

async_success_command_interface_->get().set_value(ASYNC_WAITING);
write_success &= async_success_command_interface_->get().set_value(ASYNC_WAITING);
async_state_ = ASYNC_WAITING;
}

} else {
RCLCPP_INFO(get_node()->get_logger(), "Received command to stop Freedrive Mode.");

abort_command_interface_->get().set_value(1.0);
write_success &= abort_command_interface_->get().set_value(1.0);

async_success_command_interface_->get().set_value(ASYNC_WAITING);
write_success &= async_success_command_interface_->get().set_value(ASYNC_WAITING);
async_state_ = ASYNC_WAITING;
}
first_log_ = true;
change_requested_ = false;

if (!write_success) {
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to a command interfaces.");
return controller_interface::return_type::ERROR;
}
}

if ((async_state_ == 1.0) && (first_log_)) {
Expand Down
48 changes: 25 additions & 23 deletions ur_controllers/src/gpio_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -345,8 +345,8 @@ bool GPIOController::setIO(ur_msgs::srv::SetIO::Request::SharedPtr req, ur_msgs:
{
if (req->fun == req->FUN_SET_DIGITAL_OUT && req->pin >= 0 && req->pin <= 17) {
// io async success
command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
command_interfaces_[req->pin].set_value(static_cast<double>(req->state));
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[req->pin].set_value(static_cast<double>(req->state));

RCLCPP_INFO(get_node()->get_logger(), "Setting digital output '%d' to state: '%1.0f'.", req->pin, req->state);

Expand All @@ -359,8 +359,9 @@ bool GPIOController::setIO(ur_msgs::srv::SetIO::Request::SharedPtr req, ur_msgs:
return resp->success;
} else if (req->fun == req->FUN_SET_ANALOG_OUT && req->pin >= 0 && req->pin <= 2) {
// io async success
command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->pin].set_value(static_cast<double>(req->state));
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->pin].set_value(
static_cast<double>(req->state));

RCLCPP_INFO(get_node()->get_logger(), "Setting analog output '%d' to state: '%f'.", req->pin, req->state);

Expand All @@ -372,8 +373,8 @@ bool GPIOController::setIO(ur_msgs::srv::SetIO::Request::SharedPtr req, ur_msgs:
resp->success = static_cast<bool>(command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].get_value());
return resp->success;
} else if (req->fun == req->FUN_SET_TOOL_VOLTAGE) {
command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
command_interfaces_[CommandInterfaces::TOOL_VOLTAGE_CMD].set_value(static_cast<double>(req->state));
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::TOOL_VOLTAGE_CMD].set_value(static_cast<double>(req->state));

RCLCPP_INFO(get_node()->get_logger(), "Setting tool voltage to: '%1.0f'.", req->state);

Expand Down Expand Up @@ -407,16 +408,17 @@ bool GPIOController::setAnalogOutput(ur_msgs::srv::SetAnalogOutput::Request::Sha
return false;
}

if (req->data.pin < 0 || req->data.pin > 1) {
if (!(req->data.pin == 0 || req->data.pin == 1)) {

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it a digital pin?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, but that't the pin index. There are only pins 0 and 1. It's not the analog value.

RCLCPP_ERROR(get_node()->get_logger(), "Invalid pin selected. Only pins 0 and 1 are allowed.");
resp->success = false;
return false;
}

command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->data.pin].set_value(
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->data.pin].set_value(
static_cast<float>(req->data.state));
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_DOMAIN].set_value(static_cast<double>(req->data.domain));
std::ignore =
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_DOMAIN].set_value(static_cast<double>(req->data.domain));

RCLCPP_INFO(get_node()->get_logger(), "Setting analog output '%d' to state: '%f' in domain %s.", req->data.pin,
req->data.state, domain_string.c_str());
Expand All @@ -436,9 +438,9 @@ bool GPIOController::setSpeedSlider(ur_msgs::srv::SetSpeedSliderFraction::Reques
if (req->speed_slider_fraction >= 0.01 && req->speed_slider_fraction <= 1.0) {
RCLCPP_INFO(get_node()->get_logger(), "Setting speed slider to %.2f%%.", req->speed_slider_fraction * 100.0);
// reset success flag
command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
// set commanding value for speed slider
command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_CMD].set_value(
std::ignore = command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_CMD].set_value(
static_cast<double>(req->speed_slider_fraction));

if (!waitForAsyncCommand([&]() {
Expand All @@ -462,9 +464,9 @@ bool GPIOController::resendRobotProgram(std_srvs::srv::Trigger::Request::SharedP
std_srvs::srv::Trigger::Response::SharedPtr resp)
{
// reset success flag
command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
// call the service in the hardware
command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_CMD].set_value(1.0);
std::ignore = command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_CMD].set_value(1.0);

if (!waitForAsyncCommand(
[&]() { return command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_ASYNC_SUCCESS].get_value(); })) {
Expand All @@ -488,9 +490,9 @@ bool GPIOController::handBackControl(std_srvs::srv::Trigger::Request::SharedPtr
std_srvs::srv::Trigger::Response::SharedPtr resp)
{
// reset success flag
command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
// call the service in the hardware
command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_CMD].set_value(1.0);
std::ignore = command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_CMD].set_value(1.0);

if (!waitForAsyncCommand(
[&]() { return command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_ASYNC_SUCCESS].get_value(); })) {
Expand All @@ -514,12 +516,12 @@ bool GPIOController::setPayload(const ur_msgs::srv::SetPayload::Request::SharedP
ur_msgs::srv::SetPayload::Response::SharedPtr resp)
{
// reset success flag
command_interfaces_[CommandInterfaces::PAYLOAD_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_ASYNC_SUCCESS].set_value(ASYNC_WAITING);

command_interfaces_[CommandInterfaces::PAYLOAD_MASS].set_value(req->mass);
command_interfaces_[CommandInterfaces::PAYLOAD_COG_X].set_value(req->center_of_gravity.x);
command_interfaces_[CommandInterfaces::PAYLOAD_COG_Y].set_value(req->center_of_gravity.y);
command_interfaces_[CommandInterfaces::PAYLOAD_COG_Z].set_value(req->center_of_gravity.z);
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_MASS].set_value(req->mass);
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_X].set_value(req->center_of_gravity.x);
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_Y].set_value(req->center_of_gravity.y);
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_Z].set_value(req->center_of_gravity.z);

if (!waitForAsyncCommand(
[&]() { return command_interfaces_[CommandInterfaces::PAYLOAD_ASYNC_SUCCESS].get_value(); })) {
Expand All @@ -543,9 +545,9 @@ bool GPIOController::zeroFTSensor(std_srvs::srv::Trigger::Request::SharedPtr /*r
std_srvs::srv::Trigger::Response::SharedPtr resp)
{
// reset success flag
command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
std::ignore = command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
// call the service in the hardware
command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_CMD].set_value(1.0);
std::ignore = command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_CMD].set_value(1.0);

if (!waitForAsyncCommand(
[&]() { return command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_ASYNC_SUCCESS].get_value(); })) {
Expand Down
Loading
Loading