Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove all build warnings #1233

Merged
merged 4 commits into from
Jan 17, 2025
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
Original file line number Diff line number Diff line change
Expand Up @@ -37,17 +37,17 @@
#pragma once
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <realtime_tools/realtime_buffer.h>
#include <array>
#include <memory>

#include <controller_interface/controller_interface.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <realtime_tools/realtime_buffer.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/trigger.hpp>
#include <ur_msgs/srv/set_force_mode.hpp>

#include "force_mode_controller_parameters.hpp"
#include "ur_controllers/force_mode_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@
#include <rclcpp/duration.hpp>
#include "std_msgs/msg/bool.hpp"

#include "freedrive_mode_controller_parameters.hpp"
#include "ur_controllers/freedrive_mode_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
2 changes: 1 addition & 1 deletion ur_controllers/include/ur_controllers/gpio_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
#include "std_msgs/msg/bool.hpp"
#include "gpio_controller_parameters.hpp"
#include "ur_controllers/gpio_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,6 @@

#include <stdint.h>

#include <realtime_tools/realtime_buffer.h>
#include <realtime_tools/realtime_server_goal_handle.h>

#include <functional>
#include <limits>
#include <memory>
Expand All @@ -54,6 +51,8 @@
#include <vector>

#include <controller_interface/controller_interface.hpp>
#include <realtime_tools/realtime_buffer.hpp>
#include <realtime_tools/realtime_server_goal_handle.hpp>
#include <rclcpp_action/server.hpp>
#include <rclcpp_action/create_server.hpp>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -65,7 +64,7 @@
#include <trajectory_msgs/msg/joint_trajectory.hpp>
#include <control_msgs/action/follow_joint_trajectory.hpp>

#include "passthrough_trajectory_controller_parameters.hpp"
#include "ur_controllers/passthrough_trajectory_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
#include "scaled_joint_trajectory_controller_parameters.hpp"
#include "ur_controllers/scaled_joint_trajectory_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
#include "std_msgs/msg/float64.hpp"
#include "speed_scaling_state_broadcaster_parameters.hpp"
#include "ur_controllers/speed_scaling_state_broadcaster_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@
#include <memory>

#include <controller_interface/controller_interface.hpp>
#include <realtime_tools/realtime_box.h>
#include <realtime_tools/realtime_box.hpp>

#include "ur_msgs/srv/get_robot_software_version.hpp"
#include "ur_configuration_controller_parameters.hpp"
#include "ur_controllers/ur_configuration_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
1 change: 1 addition & 0 deletions ur_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@

<depend>angles</depend>
<depend>controller_interface</depend>
<depend>generate_parameter_library</depend>
<depend>geometry_msgs</depend>
<depend>hardware_interface</depend>
<depend>joint_trajectory_controller</depend>
Expand Down
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
Loading
Loading