Skip to content

Commit

Permalink
Add parameter check for geometric values (backport #1120) (#1125)
Browse files Browse the repository at this point in the history
  • Loading branch information
mergify[bot] authored May 22, 2024
1 parent e094656 commit 2dabd0c
Show file tree
Hide file tree
Showing 8 changed files with 178 additions and 203 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]
}
}
6 changes: 3 additions & 3 deletions diff_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,7 @@ if(BUILD_TESTING)
find_package(ros2_control_test_assets REQUIRED)

ament_add_gmock(test_diff_drive_controller
test/test_diff_drive_controller.cpp
ENV config_file=${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_diff_drive_controller.yaml)
test/test_diff_drive_controller.cpp)
target_link_libraries(test_diff_drive_controller
diff_drive_controller
)
Expand All @@ -69,8 +68,9 @@ if(BUILD_TESTING)
tf2_msgs
)

ament_add_gmock(test_load_diff_drive_controller
add_rostest_with_parameters_gmock(test_load_diff_drive_controller
test/test_load_diff_drive_controller.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_diff_drive_controller.yaml
)
ament_target_dependencies(test_load_diff_drive_controller
controller_manager
Expand Down
16 changes: 14 additions & 2 deletions diff_drive_controller/src/diff_drive_controller_parameter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,26 @@ diff_drive_controller:
left_wheel_names: {
type: string_array,
default_value: [],
description: "Link names of the left side wheels",
description: "Names of the left side wheels' joints",
validation: {
not_empty<>: []
}
}
right_wheel_names: {
type: string_array,
default_value: [],
description: "Link names of the right side wheels",
description: "Names of the right side wheels' joints",
validation: {
not_empty<>: []
}
}
wheel_separation: {
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]
}
}
wheels_per_side: {
type: int,
Expand All @@ -23,6 +32,9 @@ diff_drive_controller:
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
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@ test_diff_drive_controller:
ros__parameters:
left_wheel_names: ["left_wheels"]
right_wheel_names: ["right_wheels"]
write_op_modes: ["motor_controller"]

wheel_separation: 0.40
wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
Expand All @@ -21,7 +20,7 @@ test_diff_drive_controller:
open_loop: true
enable_odom_tf: true

cmd_vel_timeout: 500 # milliseconds
cmd_vel_timeout: 0.5 # seconds
publish_limited_velocity: true
velocity_rolling_window_size: 10

Expand Down
Loading

0 comments on commit 2dabd0c

Please sign in to comment.