Skip to content

Commit ee89eed

Browse files
authored
Remove all build warnings (#1233)
* Update realtime_tools header extensions * Handle nodiscard return value of command_interface.set_value Fail the controller function if writing to a command interface fails. For the GPIO controller we ignore the return value, as we are checking the result anyway. * Use new path of including generated parameter headers * Add missing generate_parameter_library dependency in package.xml
1 parent 79252cf commit ee89eed

14 files changed

+158
-98
lines changed

ur_controllers/include/ur_controllers/force_mode_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,17 +37,17 @@
3737
#pragma once
3838
#include <tf2_ros/buffer.h>
3939
#include <tf2_ros/transform_listener.h>
40-
#include <realtime_tools/realtime_buffer.h>
4140
#include <array>
4241
#include <memory>
4342

4443
#include <controller_interface/controller_interface.hpp>
4544
#include <geometry_msgs/msg/pose_stamped.hpp>
45+
#include <realtime_tools/realtime_buffer.hpp>
4646
#include <rclcpp/rclcpp.hpp>
4747
#include <std_srvs/srv/trigger.hpp>
4848
#include <ur_msgs/srv/set_force_mode.hpp>
4949

50-
#include "force_mode_controller_parameters.hpp"
50+
#include "ur_controllers/force_mode_controller_parameters.hpp"
5151

5252
namespace ur_controllers
5353
{

ur_controllers/include/ur_controllers/freedrive_mode_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@
5353
#include <rclcpp/duration.hpp>
5454
#include "std_msgs/msg/bool.hpp"
5555

56-
#include "freedrive_mode_controller_parameters.hpp"
56+
#include "ur_controllers/freedrive_mode_controller_parameters.hpp"
5757

5858
namespace ur_controllers
5959
{

ur_controllers/include/ur_controllers/gpio_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@
5757
#include "rclcpp/time.hpp"
5858
#include "rclcpp/duration.hpp"
5959
#include "std_msgs/msg/bool.hpp"
60-
#include "gpio_controller_parameters.hpp"
60+
#include "ur_controllers/gpio_controller_parameters.hpp"
6161

6262
namespace ur_controllers
6363
{

ur_controllers/include/ur_controllers/passthrough_trajectory_controller.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,6 @@
4343

4444
#include <stdint.h>
4545

46-
#include <realtime_tools/realtime_buffer.h>
47-
#include <realtime_tools/realtime_server_goal_handle.h>
48-
4946
#include <functional>
5047
#include <limits>
5148
#include <memory>
@@ -54,6 +51,8 @@
5451
#include <vector>
5552

5653
#include <controller_interface/controller_interface.hpp>
54+
#include <realtime_tools/realtime_buffer.hpp>
55+
#include <realtime_tools/realtime_server_goal_handle.hpp>
5756
#include <rclcpp_action/server.hpp>
5857
#include <rclcpp_action/create_server.hpp>
5958
#include <rclcpp/rclcpp.hpp>
@@ -65,7 +64,7 @@
6564
#include <trajectory_msgs/msg/joint_trajectory.hpp>
6665
#include <control_msgs/action/follow_joint_trajectory.hpp>
6766

68-
#include "passthrough_trajectory_controller_parameters.hpp"
67+
#include "ur_controllers/passthrough_trajectory_controller_parameters.hpp"
6968

7069
namespace ur_controllers
7170
{

ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@
4545
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
4646
#include "rclcpp/time.hpp"
4747
#include "rclcpp/duration.hpp"
48-
#include "scaled_joint_trajectory_controller_parameters.hpp"
48+
#include "ur_controllers/scaled_joint_trajectory_controller_parameters.hpp"
4949

5050
namespace ur_controllers
5151
{

ur_controllers/include/ur_controllers/speed_scaling_state_broadcaster.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@
4848
#include "rclcpp/time.hpp"
4949
#include "rclcpp/duration.hpp"
5050
#include "std_msgs/msg/float64.hpp"
51-
#include "speed_scaling_state_broadcaster_parameters.hpp"
51+
#include "ur_controllers/speed_scaling_state_broadcaster_parameters.hpp"
5252

5353
namespace ur_controllers
5454
{

ur_controllers/include/ur_controllers/ur_configuration_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,10 +44,10 @@
4444
#include <memory>
4545

4646
#include <controller_interface/controller_interface.hpp>
47-
#include <realtime_tools/realtime_box.h>
47+
#include <realtime_tools/realtime_box.hpp>
4848

4949
#include "ur_msgs/srv/get_robot_software_version.hpp"
50-
#include "ur_configuration_controller_parameters.hpp"
50+
#include "ur_controllers/ur_configuration_controller_parameters.hpp"
5151

5252
namespace ur_controllers
5353
{

ur_controllers/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525

2626
<depend>angles</depend>
2727
<depend>controller_interface</depend>
28+
<depend>generate_parameter_library</depend>
2829
<depend>geometry_msgs</depend>
2930
<depend>hardware_interface</depend>
3031
<depend>joint_trajectory_controller</depend>

ur_controllers/src/force_mode_controller.cpp

Lines changed: 62 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,9 @@ controller_interface::CallbackReturn
156156
ur_controllers::ForceModeController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
157157
{
158158
// Stop force mode if this controller is deactivated.
159-
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
159+
if (!command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0)) {
160+
return LifecycleNodeInterface::CallbackReturn::ERROR;
161+
}
160162
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
161163
}
162164

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

176178
// Publish state of force_mode?
177179
if (change_requested_) {
180+
bool write_successful = true;
178181
if (force_mode_active_) {
179182
const auto force_mode_parameters = force_mode_params_buffer_.readFromRT();
180-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value(force_mode_parameters->task_frame[0]);
181-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value(force_mode_parameters->task_frame[1]);
182-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value(force_mode_parameters->task_frame[2]);
183-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value(force_mode_parameters->task_frame[3]);
184-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value(force_mode_parameters->task_frame[4]);
185-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value(force_mode_parameters->task_frame[5]);
186-
187-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value(
183+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value(
184+
force_mode_parameters->task_frame[0]);
185+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value(
186+
force_mode_parameters->task_frame[1]);
187+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value(
188+
force_mode_parameters->task_frame[2]);
189+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value(
190+
force_mode_parameters->task_frame[3]);
191+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value(
192+
force_mode_parameters->task_frame[4]);
193+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value(
194+
force_mode_parameters->task_frame[5]);
195+
196+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value(
188197
force_mode_parameters->selection_vec[0]);
189-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value(
198+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value(
190199
force_mode_parameters->selection_vec[1]);
191-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value(
200+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value(
192201
force_mode_parameters->selection_vec[2]);
193-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value(
202+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value(
194203
force_mode_parameters->selection_vec[3]);
195-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value(
204+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value(
196205
force_mode_parameters->selection_vec[4]);
197-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value(
206+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value(
198207
force_mode_parameters->selection_vec[5]);
199208

200-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(force_mode_parameters->wrench.force.x);
201-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(force_mode_parameters->wrench.force.y);
202-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(force_mode_parameters->wrench.force.z);
203-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(force_mode_parameters->wrench.torque.x);
204-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(force_mode_parameters->wrench.torque.y);
205-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(force_mode_parameters->wrench.torque.z);
206-
207-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value(force_mode_parameters->limits[0]);
208-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value(force_mode_parameters->limits[1]);
209-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value(force_mode_parameters->limits[2]);
210-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value(force_mode_parameters->limits[3]);
211-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value(force_mode_parameters->limits[4]);
212-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value(force_mode_parameters->limits[5]);
213-
214-
command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value(force_mode_parameters->type);
215-
command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value(force_mode_parameters->damping_factor);
216-
command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value(force_mode_parameters->gain_scaling);
209+
write_successful &=
210+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(force_mode_parameters->wrench.force.x);
211+
write_successful &=
212+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(force_mode_parameters->wrench.force.y);
213+
write_successful &=
214+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(force_mode_parameters->wrench.force.z);
215+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(
216+
force_mode_parameters->wrench.torque.x);
217+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(
218+
force_mode_parameters->wrench.torque.y);
219+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(
220+
force_mode_parameters->wrench.torque.z);
221+
222+
write_successful &=
223+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value(force_mode_parameters->limits[0]);
224+
write_successful &=
225+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value(force_mode_parameters->limits[1]);
226+
write_successful &=
227+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value(force_mode_parameters->limits[2]);
228+
write_successful &=
229+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value(force_mode_parameters->limits[3]);
230+
write_successful &=
231+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value(force_mode_parameters->limits[4]);
232+
write_successful &=
233+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value(force_mode_parameters->limits[5]);
234+
235+
write_successful &=
236+
command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value(force_mode_parameters->type);
237+
write_successful &=
238+
command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value(force_mode_parameters->damping_factor);
239+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value(
240+
force_mode_parameters->gain_scaling);
217241

218242
// Signal that we are waiting for confirmation that force mode is activated
219-
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
243+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
220244
async_state_ = ASYNC_WAITING;
221245
} else {
222-
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
223-
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
246+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
247+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
224248
async_state_ = ASYNC_WAITING;
225249
}
250+
if (!write_successful) {
251+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to a command interfaces.");
252+
return controller_interface::return_type::ERROR;
253+
}
226254
change_requested_ = false;
227255
}
228256

ur_controllers/src/freedrive_mode_controller.cpp

Lines changed: 18 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,10 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
153153
[&](auto& interface) { return (interface.get_name() == interface_name); });
154154
if (it != command_interfaces_.end()) {
155155
abort_command_interface_ = *it;
156-
abort_command_interface_->get().set_value(0.0);
156+
if (!abort_command_interface_->get().set_value(0.0)) {
157+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to abort command interface.");
158+
return controller_interface::CallbackReturn::ERROR;
159+
}
157160
} else {
158161
RCLCPP_ERROR(get_node()->get_logger(), "Did not find '%s' in command interfaces.", interface_name.c_str());
159162
return controller_interface::CallbackReturn::ERROR;
@@ -166,7 +169,10 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
166169
controller_interface::CallbackReturn
167170
ur_controllers::FreedriveModeController::on_cleanup(const rclcpp_lifecycle::State& /*previous_state*/)
168171
{
169-
abort_command_interface_->get().set_value(1.0);
172+
if (!abort_command_interface_->get().set_value(1.0)) {
173+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to abort command interface.");
174+
return controller_interface::CallbackReturn::ERROR;
175+
}
170176

171177
stop_logging_thread();
172178

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

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

204211
// Set command interface to enable
205-
enable_command_interface_->get().set_value(1.0);
212+
write_success &= enable_command_interface_->get().set_value(1.0);
206213

207-
async_success_command_interface_->get().set_value(ASYNC_WAITING);
214+
write_success &= async_success_command_interface_->get().set_value(ASYNC_WAITING);
208215
async_state_ = ASYNC_WAITING;
209216
}
210217

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

214-
abort_command_interface_->get().set_value(1.0);
221+
write_success &= abort_command_interface_->get().set_value(1.0);
215222

216-
async_success_command_interface_->get().set_value(ASYNC_WAITING);
223+
write_success &= async_success_command_interface_->get().set_value(ASYNC_WAITING);
217224
async_state_ = ASYNC_WAITING;
218225
}
219226
first_log_ = true;
220227
change_requested_ = false;
228+
229+
if (!write_success) {
230+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to a command interfaces.");
231+
return controller_interface::return_type::ERROR;
232+
}
221233
}
222234

223235
if ((async_state_ == 1.0) && (first_log_)) {

0 commit comments

Comments
 (0)