Skip to content

Commit

Permalink
Add check also for tricycle_controller
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed May 7, 2024
1 parent 665340d commit 9b99062
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 0 deletions.
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

0 comments on commit 9b99062

Please sign in to comment.