Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use the custom validators directly from control_toolbox #1504

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Use the custom validators directly from control_toolbox
  • Loading branch information
christophfroehlich committed Jan 22, 2025
commit ca6e9da6cee57d55ceba05afe3bfa0fe3c36c62f
7 changes: 5 additions & 2 deletions diff_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,11 @@ endforeach()
add_compile_definitions(RCPPUTILS_VERSION_MAJOR=${rcpputils_VERSION_MAJOR})
add_compile_definitions(RCPPUTILS_VERSION_MINOR=${rcpputils_VERSION_MINOR})

# get include dirs from control_toolbox for the custom validators
get_target_property(TB_INCLUDE_DIRS control_toolbox::rate_limiter_parameters INTERFACE_INCLUDE_DIRECTORIES)
generate_parameter_library(diff_drive_controller_parameters
src/diff_drive_controller_parameter.yaml
include/diff_drive_controller/custom_validators.hpp
${TB_INCLUDE_DIRS}/control_toolbox/custom_validators.hpp
)

add_library(diff_drive_controller SHARED
Expand All @@ -51,7 +53,8 @@ target_include_directories(diff_drive_controller PUBLIC
)
target_link_libraries(diff_drive_controller
PUBLIC
diff_drive_controller_parameters)
diff_drive_controller_parameters
control_toolbox::rate_limiter_parameters)
ament_target_dependencies(diff_drive_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
pluginlib_export_plugin_description_file(controller_interface diff_drive_plugin.xml)

Expand Down

This file was deleted.

32 changes: 16 additions & 16 deletions diff_drive_controller/src/diff_drive_controller_parameter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -132,30 +132,30 @@ diff_drive_controller:
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
min_velocity: {
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
max_acceleration: {
type: double,
default_value: .NAN,
description: "Maximum acceleration in forward direction.",
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
max_deceleration: {
type: double,
default_value: .NAN,
description: "Maximum deceleration in forward direction.",
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
min_acceleration: {
Expand All @@ -168,29 +168,29 @@ diff_drive_controller:
default_value: .NAN,
description: "Maximum acceleration in reverse direction. If not set, -max_acceleration will be used.",
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
max_deceleration_reverse: {
type: double,
default_value: .NAN,
description: "Maximum deceleration in reverse direction. If not set, -max_deceleration will be used.",
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
max_jerk: {
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
min_jerk: {
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
angular:
Expand All @@ -214,30 +214,30 @@ diff_drive_controller:
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
min_velocity: {
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
max_acceleration: {
type: double,
default_value: .NAN,
description: "Maximum acceleration in positive direction.",
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
max_deceleration: {
type: double,
default_value: .NAN,
description: "Maximum deceleration in positive direction.",
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
min_acceleration: {
Expand All @@ -250,28 +250,28 @@ diff_drive_controller:
default_value: .NAN,
description: "Maximum acceleration in negative direction. If not set, -max_acceleration will be used.",
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
max_deceleration_reverse: {
type: double,
default_value: .NAN,
description: "Maximum deceleration in negative direction. If not set, -max_deceleration will be used.",
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
max_jerk: {
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::gt_eq_or_nan<>": [0.0]
"control_filters::gt_eq_or_nan<>": [0.0]
}
}
min_jerk: {
type: double,
default_value: .NAN,
validation: {
"diff_drive_controller::lt_eq_or_nan<>": [0.0]
"control_filters::lt_eq_or_nan<>": [0.0]
}
}
Loading