Skip to content

Commit 7170328

Browse files
Add parameter check for geometric values (#1120)
1 parent 009f946 commit 7170328

File tree

7 files changed

+55
-0
lines changed

7 files changed

+55
-0
lines changed

ackermann_steering_controller/src/ackermann_steering_controller.yaml

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@ ackermann_steering_controller:
55
default_value: 0.0,
66
description: "Front wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
77
read_only: false,
8+
validation: {
9+
gt<>: [0.0]
10+
}
811
}
912

1013
rear_wheel_track:
@@ -13,6 +16,9 @@ ackermann_steering_controller:
1316
default_value: 0.0,
1417
description: "Rear wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
1518
read_only: false,
19+
validation: {
20+
gt<>: [0.0]
21+
}
1622
}
1723

1824
wheelbase:
@@ -21,6 +27,9 @@ ackermann_steering_controller:
2127
default_value: 0.0,
2228
description: "Distance between front and rear wheels. For details see: https://en.wikipedia.org/wiki/Wheelbase",
2329
read_only: false,
30+
validation: {
31+
gt<>: [0.0]
32+
}
2433
}
2534

2635
front_wheels_radius:
@@ -29,6 +38,9 @@ ackermann_steering_controller:
2938
default_value: 0.0,
3039
description: "Front wheels radius.",
3140
read_only: false,
41+
validation: {
42+
gt<>: [0.0]
43+
}
3244
}
3345

3446
rear_wheels_radius:
@@ -37,4 +49,7 @@ ackermann_steering_controller:
3749
default_value: 0.0,
3850
description: "Rear wheels radius.",
3951
read_only: false,
52+
validation: {
53+
gt<>: [0.0]
54+
}
4055
}

bicycle_steering_controller/src/bicycle_steering_controller.yaml

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@ bicycle_steering_controller:
55
default_value: 0.0,
66
description: "Distance between front and rear wheel. For details see: https://en.wikipedia.org/wiki/Wheelbase",
77
read_only: false,
8+
validation: {
9+
gt<>: [0.0]
10+
}
811
}
912

1013
front_wheel_radius:
@@ -13,6 +16,9 @@ bicycle_steering_controller:
1316
default_value: 0.0,
1417
description: "Front wheel radius.",
1518
read_only: false,
19+
validation: {
20+
gt<>: [0.0]
21+
}
1622
}
1723

1824
rear_wheel_radius:
@@ -21,4 +27,7 @@ bicycle_steering_controller:
2127
default_value: 0.0,
2228
description: "Rear wheel radius.",
2329
read_only: false,
30+
validation: {
31+
gt<>: [0.0]
32+
}
2433
}

diff_drive_controller/src/diff_drive_controller_parameter.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,11 +19,17 @@ diff_drive_controller:
1919
type: double,
2020
default_value: 0.0,
2121
description: "Shortest distance between the left and right wheels. If this parameter is wrong, the robot will not behave correctly in curves.",
22+
validation: {
23+
gt<>: [0.0]
24+
}
2225
}
2326
wheel_radius: {
2427
type: double,
2528
default_value: 0.0,
2629
description: "Radius of a wheel, i.e., wheels size, used for transformation of linear velocity into wheel rotations. If this parameter is wrong the robot will move faster or slower then expected.",
30+
validation: {
31+
gt<>: [0.0]
32+
}
2733
}
2834
wheel_separation_multiplier: {
2935
type: double,

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -184,6 +184,10 @@ class TestDiffDriveController : public ::testing::Test
184184
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_joints_init)));
185185
parameter_overrides.push_back(
186186
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_joints_init)));
187+
// default parameters
188+
parameter_overrides.push_back(
189+
rclcpp::Parameter("wheel_separation", rclcpp::ParameterValue(1.0)));
190+
parameter_overrides.push_back(rclcpp::Parameter("wheel_radius", rclcpp::ParameterValue(0.1)));
187191

188192
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
189193
node_options.parameter_overrides(parameter_overrides);

tricycle_controller/src/tricycle_controller_parameter.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,11 +19,17 @@ tricycle_controller:
1919
type: double,
2020
default_value: 0.0,
2121
description: "Shortest distance between the front wheel and the rear axle. If this parameter is wrong, the robot will not behave correctly in curves.",
22+
validation: {
23+
gt<>: [0.0]
24+
}
2225
}
2326
wheel_radius: {
2427
type: double,
2528
default_value: 0.0,
2629
description: "Radius of a wheel, i.e., wheels size, used for transformation of linear velocity into wheel rotations. If this parameter is wrong the robot will move faster or slower then expected.",
30+
validation: {
31+
gt<>: [0.0]
32+
}
2733
}
2834
odom_frame_id: {
2935
type: string,

tricycle_controller/test/test_tricycle_controller.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -164,6 +164,9 @@ class TestTricycleController : public ::testing::Test
164164
rclcpp::Parameter("traction_joint_name", rclcpp::ParameterValue(traction_joint_name_init)));
165165
parameter_overrides.push_back(
166166
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name_init)));
167+
// default parameters
168+
parameter_overrides.push_back(rclcpp::Parameter("wheelbase", rclcpp::ParameterValue(1.)));
169+
parameter_overrides.push_back(rclcpp::Parameter("wheel_radius", rclcpp::ParameterValue(0.1)));
167170

168171
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
169172
node_options.parameter_overrides(parameter_overrides);

tricycle_steering_controller/src/tricycle_steering_controller.yaml

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@ tricycle_steering_controller:
55
default_value: 0.0,
66
description: "Wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
77
read_only: false,
8+
validation: {
9+
gt<>: [0.0]
10+
}
811
}
912

1013
wheelbase:
@@ -13,6 +16,9 @@ tricycle_steering_controller:
1316
default_value: 0.0,
1417
description: "Distance between front and rear wheels. For details see: https://en.wikipedia.org/wiki/Wheelbase",
1518
read_only: false,
19+
validation: {
20+
gt<>: [0.0]
21+
}
1622
}
1723

1824
front_wheels_radius:
@@ -21,6 +27,9 @@ tricycle_steering_controller:
2127
default_value: 0.0,
2228
description: "Front wheels radius.",
2329
read_only: false,
30+
validation: {
31+
gt<>: [0.0]
32+
}
2433
}
2534

2635
rear_wheels_radius:
@@ -29,4 +38,7 @@ tricycle_steering_controller:
2938
default_value: 0.0,
3039
description: "Rear wheels radius.",
3140
read_only: false,
41+
validation: {
42+
gt<>: [0.0]
43+
}
3244
}

0 commit comments

Comments
 (0)