Skip to content

Commit c71ee90

Browse files
christophfroehlichpac48
authored andcommitted
[diff_drive] Remove unused parameter and add simple validation #abi-breaking (ros-controls#958)
1 parent 858b4c5 commit c71ee90

File tree

7 files changed

+143
-219
lines changed

7 files changed

+143
-219
lines changed

diff_drive_controller/CMakeLists.txt

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -53,8 +53,7 @@ if(BUILD_TESTING)
5353
find_package(ros2_control_test_assets REQUIRED)
5454

5555
ament_add_gmock(test_diff_drive_controller
56-
test/test_diff_drive_controller.cpp
57-
ENV config_file=${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_diff_drive_controller.yaml)
56+
test/test_diff_drive_controller.cpp)
5857
target_link_libraries(test_diff_drive_controller
5958
diff_drive_controller
6059
)
@@ -69,8 +68,9 @@ if(BUILD_TESTING)
6968
tf2_msgs
7069
)
7170

72-
ament_add_gmock(test_load_diff_drive_controller
71+
add_rostest_with_parameters_gmock(test_load_diff_drive_controller
7372
test/test_load_diff_drive_controller.cpp
73+
${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_diff_drive_controller.yaml
7474
)
7575
ament_target_dependencies(test_load_diff_drive_controller
7676
controller_manager

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,12 @@ class DiffDriveController : public controller_interface::ControllerInterface
110110
// Parameters from ROS for diff_drive_controller
111111
std::shared_ptr<ParamListener> param_listener_;
112112
Params params_;
113+
/* Number of wheels on each side of the robot. This is important to take the wheels slip into
114+
* account when multiple wheels on each side are present. If there are more wheels then control
115+
* signals for each side, you should enter number for control signals. For example, Husky has two
116+
* wheels on each side, but they use one control signal, in this case '1' is the correct value of
117+
* the parameter. */
118+
int wheels_per_side_;
113119

114120
Odometry odometry_;
115121

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 5 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -149,7 +149,7 @@ controller_interface::return_type DiffDriveController::update(
149149
{
150150
double left_feedback_mean = 0.0;
151151
double right_feedback_mean = 0.0;
152-
for (size_t index = 0; index < static_cast<size_t>(params_.wheels_per_side); ++index)
152+
for (size_t index = 0; index < static_cast<size_t>(wheels_per_side_); ++index)
153153
{
154154
const double left_feedback = registered_left_wheel_handles_[index].feedback.get().get_value();
155155
const double right_feedback =
@@ -166,8 +166,8 @@ controller_interface::return_type DiffDriveController::update(
166166
left_feedback_mean += left_feedback;
167167
right_feedback_mean += right_feedback;
168168
}
169-
left_feedback_mean /= static_cast<double>(params_.wheels_per_side);
170-
right_feedback_mean /= static_cast<double>(params_.wheels_per_side);
169+
left_feedback_mean /= static_cast<double>(wheels_per_side_);
170+
right_feedback_mean /= static_cast<double>(wheels_per_side_);
171171

172172
if (params_.position_feedback)
173173
{
@@ -257,7 +257,7 @@ controller_interface::return_type DiffDriveController::update(
257257
(linear_command + angular_command * wheel_separation / 2.0) / right_wheel_radius;
258258

259259
// Set wheels velocities:
260-
for (size_t index = 0; index < static_cast<size_t>(params_.wheels_per_side); ++index)
260+
for (size_t index = 0; index < static_cast<size_t>(wheels_per_side_); ++index)
261261
{
262262
registered_left_wheel_handles_[index].velocity.get().set_value(velocity_left);
263263
registered_right_wheel_handles_[index].velocity.get().set_value(velocity_right);
@@ -286,12 +286,6 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
286286
return controller_interface::CallbackReturn::ERROR;
287287
}
288288

289-
if (params_.left_wheel_names.empty())
290-
{
291-
RCLCPP_ERROR(logger, "Wheel names parameters are empty!");
292-
return controller_interface::CallbackReturn::ERROR;
293-
}
294-
295289
const double wheel_separation = params_.wheel_separation_multiplier * params_.wheel_separation;
296290
const double left_wheel_radius = params_.left_wheel_radius_multiplier * params_.wheel_radius;
297291
const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius;
@@ -320,7 +314,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
320314
}
321315

322316
// left and right sides are both equal at this point
323-
params_.wheels_per_side = params_.left_wheel_names.size();
317+
wheels_per_side_ = static_cast<int>(params_.left_wheel_names.size());
324318

325319
if (publish_limited_velocity_)
326320
{

diff_drive_controller/src/diff_drive_controller_parameter.yaml

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -2,23 +2,24 @@ diff_drive_controller:
22
left_wheel_names: {
33
type: string_array,
44
default_value: [],
5-
description: "Link names of the left side wheels",
5+
description: "Names of the left side wheels' joints",
6+
validation: {
7+
not_empty<>: []
8+
}
69
}
710
right_wheel_names: {
811
type: string_array,
912
default_value: [],
10-
description: "Link names of the right side wheels",
13+
description: "Names of the right side wheels' joints",
14+
validation: {
15+
not_empty<>: []
16+
}
1117
}
1218
wheel_separation: {
1319
type: double,
1420
default_value: 0.0,
1521
description: "Shortest distance between the left and right wheels. If this parameter is wrong, the robot will not behave correctly in curves.",
1622
}
17-
wheels_per_side: {
18-
type: int,
19-
default_value: 0,
20-
description: "Number of wheels on each side of the robot. This is important to take the wheels slip into account when multiple wheels on each side are present. If there are more wheels then control signals for each side, you should enter number for control signals. For example, Husky has two wheels on each side, but they use one control signal, in this case '1' is the correct value of the parameter.",
21-
}
2223
wheel_radius: {
2324
type: double,
2425
default_value: 0.0,

diff_drive_controller/test/config/test_diff_drive_controller.yaml

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,6 @@ test_diff_drive_controller:
22
ros__parameters:
33
left_wheel_names: ["left_wheels"]
44
right_wheel_names: ["right_wheels"]
5-
write_op_modes: ["motor_controller"]
65

76
wheel_separation: 0.40
87
wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
@@ -21,7 +20,7 @@ test_diff_drive_controller:
2120
open_loop: true
2221
enable_odom_tf: true
2322

24-
cmd_vel_timeout: 500 # milliseconds
23+
cmd_vel_timeout: 0.5 # seconds
2524
publish_limited_velocity: true
2625
velocity_rolling_window_size: 10
2726

0 commit comments

Comments
 (0)