Skip to content

Commit

Permalink
Add parameter check for geometric values (#1120)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored May 9, 2024
1 parent 009f946 commit 7170328
Show file tree
Hide file tree
Showing 7 changed files with 55 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@ ackermann_steering_controller:
default_value: 0.0,
description: "Front wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
read_only: false,
validation: {
gt<>: [0.0]
}
}

rear_wheel_track:
Expand All @@ -13,6 +16,9 @@ ackermann_steering_controller:
default_value: 0.0,
description: "Rear wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
read_only: false,
validation: {
gt<>: [0.0]
}
}

wheelbase:
Expand All @@ -21,6 +27,9 @@ ackermann_steering_controller:
default_value: 0.0,
description: "Distance between front and rear wheels. For details see: https://en.wikipedia.org/wiki/Wheelbase",
read_only: false,
validation: {
gt<>: [0.0]
}
}

front_wheels_radius:
Expand All @@ -29,6 +38,9 @@ ackermann_steering_controller:
default_value: 0.0,
description: "Front wheels radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
}

rear_wheels_radius:
Expand All @@ -37,4 +49,7 @@ ackermann_steering_controller:
default_value: 0.0,
description: "Rear wheels radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@ bicycle_steering_controller:
default_value: 0.0,
description: "Distance between front and rear wheel. For details see: https://en.wikipedia.org/wiki/Wheelbase",
read_only: false,
validation: {
gt<>: [0.0]
}
}

front_wheel_radius:
Expand All @@ -13,6 +16,9 @@ bicycle_steering_controller:
default_value: 0.0,
description: "Front wheel radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
}

rear_wheel_radius:
Expand All @@ -21,4 +27,7 @@ bicycle_steering_controller:
default_value: 0.0,
description: "Rear wheel radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,17 @@ diff_drive_controller:
type: double,
default_value: 0.0,
description: "Shortest distance between the left and right wheels. If this parameter is wrong, the robot will not behave correctly in curves.",
validation: {
gt<>: [0.0]
}
}
wheel_radius: {
type: double,
default_value: 0.0,
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.",
validation: {
gt<>: [0.0]
}
}
wheel_separation_multiplier: {
type: double,
Expand Down
4 changes: 4 additions & 0 deletions diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,10 @@ class TestDiffDriveController : public ::testing::Test
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_joints_init)));
parameter_overrides.push_back(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_joints_init)));
// default parameters
parameter_overrides.push_back(
rclcpp::Parameter("wheel_separation", rclcpp::ParameterValue(1.0)));
parameter_overrides.push_back(rclcpp::Parameter("wheel_radius", rclcpp::ParameterValue(0.1)));

parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
node_options.parameter_overrides(parameter_overrides);
Expand Down
6 changes: 6 additions & 0 deletions tricycle_controller/src/tricycle_controller_parameter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,17 @@ tricycle_controller:
type: double,
default_value: 0.0,
description: "Shortest distance between the front wheel and the rear axle. If this parameter is wrong, the robot will not behave correctly in curves.",
validation: {
gt<>: [0.0]
}
}
wheel_radius: {
type: double,
default_value: 0.0,
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.",
validation: {
gt<>: [0.0]
}
}
odom_frame_id: {
type: string,
Expand Down
3 changes: 3 additions & 0 deletions tricycle_controller/test/test_tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,9 @@ class TestTricycleController : public ::testing::Test
rclcpp::Parameter("traction_joint_name", rclcpp::ParameterValue(traction_joint_name_init)));
parameter_overrides.push_back(
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name_init)));
// default parameters
parameter_overrides.push_back(rclcpp::Parameter("wheelbase", rclcpp::ParameterValue(1.)));
parameter_overrides.push_back(rclcpp::Parameter("wheel_radius", rclcpp::ParameterValue(0.1)));

parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
node_options.parameter_overrides(parameter_overrides);
Expand Down
12 changes: 12 additions & 0 deletions tricycle_steering_controller/src/tricycle_steering_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@ tricycle_steering_controller:
default_value: 0.0,
description: "Wheel track length. For details see: https://en.wikipedia.org/wiki/Wheelbase",
read_only: false,
validation: {
gt<>: [0.0]
}
}

wheelbase:
Expand All @@ -13,6 +16,9 @@ tricycle_steering_controller:
default_value: 0.0,
description: "Distance between front and rear wheels. For details see: https://en.wikipedia.org/wiki/Wheelbase",
read_only: false,
validation: {
gt<>: [0.0]
}
}

front_wheels_radius:
Expand All @@ -21,6 +27,9 @@ tricycle_steering_controller:
default_value: 0.0,
description: "Front wheels radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
}

rear_wheels_radius:
Expand All @@ -29,4 +38,7 @@ tricycle_steering_controller:
default_value: 0.0,
description: "Rear wheels radius.",
read_only: false,
validation: {
gt<>: [0.0]
}
}

0 comments on commit 7170328

Please sign in to comment.